Skip to content

Commit

Permalink
4 to main
Browse files Browse the repository at this point in the history
Signed-off-by: Ashton Larkin <[email protected]>
  • Loading branch information
adlarkin committed Nov 12, 2020
2 parents b3a18a1 + 21b867d commit f27e234
Show file tree
Hide file tree
Showing 21 changed files with 166 additions and 33 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/pr-collection-labeler.yml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
name: PR Collection Labeler

on: pull_request
on: pull_request_target

jobs:
pr_collection_labeler:
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/triage.yml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
on:
issues:
types: [opened]
pull_request:
pull_request_target:
types: [opened]
name: Ticket opened
jobs:
Expand Down
22 changes: 22 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,28 @@

## Ignition Sensors 3

### Ignition Sensors 3.X.X (20XX-XX-XX)

### Ignition Sensors 3.1.0 (2020-09-03)

1. Update camera sensor only when needed
* [Pull request 37](https://github.com/ignitionrobotics/ign-sensors/pull/37)

1. Add noise to RGBD camera.
* [Pull Request 35](https://github.com/ignitionrobotics/ign-sensors/pull/35)

1. Fix version numbers in config.hh
* [Pull Request 42](https://github.com/ignitionrobotics/ign-sensors/pull/42)

1. Make sure all sensors have a default topic. When invalid topics are passed
in, convert them to valid topics if possible. If not possible to convert
into valid topic, fail gracefully.
* [Pull Request 33](https://github.com/ignitionrobotics/ign-sensors/pull/33)

1. GitHub migration
* [Pull request 11](https://github.com/ignitionrobotics/ign-sensors/pull/11)
* [Pull request 21](https://github.com/ignitionrobotics/ign-sensors/pull/21)

### Ignition Sensors 3.0.0 (2019-12-10)

1. Add support for sdformat frame semantics
Expand Down
11 changes: 8 additions & 3 deletions include/ignition/sensors/Manager.hh
Original file line number Diff line number Diff line change
Expand Up @@ -123,13 +123,18 @@ namespace ignition
{
T *result = dynamic_cast<T*>(this->Sensor(id));

if (!result)
ignerr << "SDF sensor type does not match template type\n";
if (nullptr == result)
{
ignerr << "Failed to create sensor [" << id << "] of type ["
<< _sdf->Get<std::string>("type")
<< "]. SDF sensor type does not match template type."
<< std::endl;
}

return result;
}

ignerr << "Failed to create sensor of type["
ignerr << "Failed to create sensor of type ["
<< _sdf->Get<std::string>("type") << "]\n";
return nullptr;
}
Expand Down
12 changes: 11 additions & 1 deletion src/Camera_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -123,6 +123,16 @@ sdf::ElementPtr CameraToSdf(const std::string &_type,
->GetElement("sensor");
}

/// \brief Test camera sensor
class Camera_TEST : public ::testing::Test
{
// Documentation inherited
protected: void SetUp() override
{
ignition::common::Console::SetVerbosity(4);
}
};

//////////////////////////////////////////////////
TEST(Camera_TEST, CreateCamera)
{
Expand All @@ -136,7 +146,7 @@ TEST(Camera_TEST, CreateCamera)
mgr.CreateSensor<ignition::sensors::CameraSensor>(camSdf);

// Make sure the above dynamic cast worked.
EXPECT_TRUE(cam != nullptr);
ASSERT_NE(nullptr, cam);

// Check topics
EXPECT_EQ("/cam", cam->Topic());
Expand Down
13 changes: 11 additions & 2 deletions src/ImuSensor_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -173,6 +173,15 @@ sdf::ElementPtr ImuSensorToSDF(const std::string &name, double update_rate,
->GetElement("sensor");
}

/// \brief Test IMU sensor
class ImuSensor_TEST : public ::testing::Test
{
// Documentation inherited
protected: void SetUp() override
{
ignition::common::Console::SetVerbosity(4);
}
};

//////////////////////////////////////////////////
TEST(ImuSensor_TEST, CreateImuSensor)
Expand Down Expand Up @@ -241,8 +250,8 @@ TEST(ImuSensor_TEST, ComputeNoise)
auto sensor = mgr.CreateSensor<ignition::sensors::ImuSensor>(imuSDF);

// Make sure the above dynamic cast worked.
EXPECT_TRUE(sensor != nullptr);
EXPECT_TRUE(sensor_truth != nullptr);
ASSERT_NE(nullptr, sensor);
ASSERT_NE(nullptr, sensor_truth);

sensor->SetAngularVelocity(math::Vector3d::Zero);
sensor->SetLinearAcceleration(math::Vector3d::Zero);
Expand Down
12 changes: 11 additions & 1 deletion src/Lidar_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,16 @@ void OnNewLaserFrame(int *_scanCounter, float *_scanDest,
*_scanCounter += 1;
}

/// \brief Test lidar sensor
class Lidar_TEST : public ::testing::Test
{
// Documentation inherited
protected: void SetUp() override
{
ignition::common::Console::SetVerbosity(4);
}
};

/////////////////////////////////////////////////
/// \brief Test Creation of a Lidar sensor
TEST(Lidar_TEST, CreateLaser)
Expand Down Expand Up @@ -124,7 +134,7 @@ TEST(Lidar_TEST, CreateLaser)
lidarSDF);

// Make sure the above dynamic cast worked.
EXPECT_TRUE(sensor != nullptr);
ASSERT_NE(nullptr, sensor);

double angleRes = (sensor->AngleMax() - sensor->AngleMin()).Radian() /
sensor->RayCount();
Expand Down
9 changes: 9 additions & 0 deletions src/Manager_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,15 @@
#include <gtest/gtest.h>
#include <ignition/sensors/Manager.hh>

/// \brief Test sensor manager
class Manager_TEST : public ::testing::Test
{
// Documentation inherited
protected: void SetUp() override
{
ignition::common::Console::SetVerbosity(4);
}
};

//////////////////////////////////////////////////
TEST(Manager, construct)
Expand Down
11 changes: 11 additions & 0 deletions src/Noise_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@

#include <numeric>

#include <ignition/common/Console.hh>
#include <ignition/math/Rand.hh>

#include "ignition/sensors/Noise.hh"
Expand Down Expand Up @@ -54,6 +55,16 @@ sdf::ElementPtr NoiseSdf(const std::string &_type, double _mean,
return sdf;
}

/// \brief Test sensor noise
class NoiseTest : public ::testing::Test
{
// Documentation inherited
protected: void SetUp() override
{
ignition::common::Console::SetVerbosity(4);
}
};

//////////////////////////////////////////////////
// Test constructor
TEST(NoiseTest, Constructor)
Expand Down
2 changes: 2 additions & 0 deletions src/PointCloudUtil.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

#include "PointCloudUtil.hh"

#include <string>

using namespace ignition;
using namespace sensors;

Expand Down
11 changes: 11 additions & 0 deletions src/Sensor_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
*/
#include <gtest/gtest.h>

#include <ignition/common/Console.hh>
#include <ignition/sensors/Export.hh>
#include <ignition/sensors/Sensor.hh>

Expand All @@ -38,6 +39,16 @@ class TestSensor : public Sensor
public: unsigned int updateCount{0};
};

/// \brief Test sensor class
class Sensor_TEST : public ::testing::Test
{
// Documentation inherited
protected: void SetUp() override
{
ignition::common::Console::SetVerbosity(4);
}
};

//////////////////////////////////////////////////
TEST(Sensor_TEST, Sensor)
{
Expand Down
14 changes: 10 additions & 4 deletions test/integration/air_pressure_plugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -99,8 +99,14 @@ sdf::ElementPtr AirPressureToSdfWithNoise(const std::string &_name,
->GetElement("sensor");
}

/// \brief Test air pressure sensor
class AirPressureSensorTest: public testing::Test
{
// Documentation inherited
protected: void SetUp() override
{
ignition::common::Console::SetVerbosity(4);
}
};

/////////////////////////////////////////////////
Expand Down Expand Up @@ -128,7 +134,7 @@ TEST_F(AirPressureSensorTest, CreateAirPressure)
sf.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib"));
std::unique_ptr<ignition::sensors::AirPressureSensor> sensor =
sf.CreateSensor<ignition::sensors::AirPressureSensor>(airPressureSdf);
EXPECT_TRUE(sensor != nullptr);
ASSERT_NE(nullptr, sensor);

EXPECT_EQ(name, sensor->Name());
EXPECT_EQ(topic, sensor->Topic());
Expand All @@ -137,7 +143,7 @@ TEST_F(AirPressureSensorTest, CreateAirPressure)
std::unique_ptr<ignition::sensors::AirPressureSensor> sensorNoise =
sf.CreateSensor<ignition::sensors::AirPressureSensor>(
airPressureSdfNoise);
EXPECT_TRUE(sensorNoise != nullptr);
ASSERT_NE(nullptr, sensorNoise);

EXPECT_EQ(name, sensorNoise->Name());
EXPECT_EQ(topicNoise, sensorNoise->Topic());
Expand Down Expand Up @@ -174,15 +180,15 @@ TEST_F(AirPressureSensorTest, SensorReadings)
dynamic_cast<ignition::sensors::AirPressureSensor *>(s.release()));

// Make sure the above dynamic cast worked.
EXPECT_TRUE(sensor != nullptr);
ASSERT_NE(nullptr, sensor);

std::unique_ptr<ignition::sensors::Sensor> sNoise =
sf.CreateSensor(airPressureSdfNoise);
std::unique_ptr<ignition::sensors::AirPressureSensor> sensorNoise(
dynamic_cast<ignition::sensors::AirPressureSensor *>(sNoise.release()));

// Make sure the above dynamic cast worked.
EXPECT_TRUE(sensorNoise != nullptr);
ASSERT_NE(nullptr, sensorNoise);

// verify initial readings
EXPECT_DOUBLE_EQ(0.0, sensor->ReferenceAltitude());
Expand Down
14 changes: 10 additions & 4 deletions test/integration/altimeter_plugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -106,8 +106,14 @@ sdf::ElementPtr AltimeterToSdfWithNoise(const std::string &_name,
->GetElement("sensor");
}

/// \brief Test altimeter sensor
class AltimeterSensorTest: public testing::Test
{
// Documentation inherited
protected: void SetUp() override
{
ignition::common::Console::SetVerbosity(4);
}
};

/////////////////////////////////////////////////
Expand Down Expand Up @@ -135,15 +141,15 @@ TEST_F(AltimeterSensorTest, CreateAltimeter)
sf.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib"));
std::unique_ptr<ignition::sensors::AltimeterSensor> sensor =
sf.CreateSensor<ignition::sensors::AltimeterSensor>(altimeterSdf);
EXPECT_TRUE(sensor != nullptr);
ASSERT_NE(nullptr, sensor);

EXPECT_EQ(name, sensor->Name());
EXPECT_EQ(topic, sensor->Topic());
EXPECT_DOUBLE_EQ(updateRate, sensor->UpdateRate());

std::unique_ptr<ignition::sensors::AltimeterSensor> sensorNoise =
sf.CreateSensor<ignition::sensors::AltimeterSensor>(altimeterSdfNoise);
EXPECT_TRUE(sensorNoise != nullptr);
ASSERT_NE(nullptr, sensorNoise);

EXPECT_EQ(name, sensorNoise->Name());
EXPECT_EQ(topicNoise, sensorNoise->Topic());
Expand Down Expand Up @@ -180,15 +186,15 @@ TEST_F(AltimeterSensorTest, SensorReadings)
dynamic_cast<ignition::sensors::AltimeterSensor *>(s.release()));

// Make sure the above dynamic cast worked.
EXPECT_TRUE(sensor != nullptr);
ASSERT_NE(nullptr, sensor);

std::unique_ptr<ignition::sensors::Sensor> sNoise =
sf.CreateSensor(altimeterSdfNoise);
std::unique_ptr<ignition::sensors::AltimeterSensor> sensorNoise(
dynamic_cast<ignition::sensors::AltimeterSensor *>(sNoise.release()));

// Make sure the above dynamic cast worked.
EXPECT_TRUE(sensorNoise != nullptr);
ASSERT_NE(nullptr, sensorNoise);

// verify initial readings
EXPECT_DOUBLE_EQ(0.0, sensor->VerticalReference());
Expand Down
2 changes: 2 additions & 0 deletions test/integration/camera_plugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,7 @@ void CameraSensorTest::ImagesWithBuiltinSDF(const std::string &_renderEngine)
ignition::rendering::unloadEngine(engine->Name());
}

//////////////////////////////////////////////////
TEST_P(CameraSensorTest, ImagesWithBuiltinSDF)
{
ImagesWithBuiltinSDF(GetParam());
Expand All @@ -99,6 +100,7 @@ INSTANTIATE_TEST_CASE_P(CameraSensor, CameraSensorTest,
//////////////////////////////////////////////////
int main(int argc, char **argv)
{
ignition::common::Console::SetVerbosity(4);
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
2 changes: 2 additions & 0 deletions test/integration/depth_camera_plugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -478,6 +478,7 @@ void DepthCameraSensorTest::ImagesWithBuiltinSDF(
ignition::rendering::unloadEngine(engine->Name());
}

//////////////////////////////////////////////////
TEST_P(DepthCameraSensorTest, ImagesWithBuiltinSDF)
{
ImagesWithBuiltinSDF(GetParam());
Expand All @@ -489,6 +490,7 @@ INSTANTIATE_TEST_CASE_P(DepthCameraSensor, DepthCameraSensorTest,
//////////////////////////////////////////////////
int main(int argc, char **argv)
{
ignition::common::Console::SetVerbosity(4);
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
Loading

0 comments on commit f27e234

Please sign in to comment.