From f2964f9a4601f62609e6fc1efc61f5de728629d1 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Tue, 3 Nov 2020 09:43:47 -0800 Subject: [PATCH 1/2] Prevent segfaults on test failures, make tests verbose Signed-off-by: Louise Poubel --- src/Camera_TEST.cc | 12 +++++++++++- src/ImuSensor_TEST.cc | 13 +++++++++++-- src/Lidar_TEST.cc | 12 +++++++++++- src/Manager_TEST.cc | 9 +++++++++ src/Noise_TEST.cc | 11 +++++++++++ src/Sensor_TEST.cc | 11 +++++++++++ test/integration/air_pressure_plugin.cc | 14 ++++++++++---- test/integration/altimeter_plugin.cc | 14 ++++++++++---- test/integration/camera_plugin.cc | 2 ++ test/integration/depth_camera_plugin.cc | 2 ++ test/integration/gpu_lidar_sensor_plugin.cc | 21 ++++++++++++++------- test/integration/imu_plugin.cc | 10 ++++++++-- test/integration/logical_camera_plugin.cc | 10 ++++++++-- test/integration/magnetometer_plugin.cc | 15 ++++++++++----- test/integration/rgbd_camera_plugin.cc | 2 ++ test/integration/thermal_camera_plugin.cc | 2 ++ 16 files changed, 132 insertions(+), 28 deletions(-) diff --git a/src/Camera_TEST.cc b/src/Camera_TEST.cc index d59fbb4b..e2fa1284 100644 --- a/src/Camera_TEST.cc +++ b/src/Camera_TEST.cc @@ -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) { @@ -136,7 +146,7 @@ TEST(Camera_TEST, CreateCamera) mgr.CreateSensor(camSdf); // Make sure the above dynamic cast worked. - EXPECT_TRUE(cam != nullptr); + ASSERT_NE(nullptr, cam); // Check topics EXPECT_EQ("/cam", cam->Topic()); diff --git a/src/ImuSensor_TEST.cc b/src/ImuSensor_TEST.cc index 7838652e..82948c25 100644 --- a/src/ImuSensor_TEST.cc +++ b/src/ImuSensor_TEST.cc @@ -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) @@ -241,8 +250,8 @@ TEST(ImuSensor_TEST, ComputeNoise) auto sensor = mgr.CreateSensor(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); diff --git a/src/Lidar_TEST.cc b/src/Lidar_TEST.cc index 27fe6a4c..a40d4b18 100644 --- a/src/Lidar_TEST.cc +++ b/src/Lidar_TEST.cc @@ -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) @@ -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(); diff --git a/src/Manager_TEST.cc b/src/Manager_TEST.cc index 791b303e..a57b2f46 100644 --- a/src/Manager_TEST.cc +++ b/src/Manager_TEST.cc @@ -18,6 +18,15 @@ #include #include +/// \brief Test sensor manager +class Manager_TEST : public ::testing::Test +{ + // Documentation inherited + protected: void SetUp() override + { + ignition::common::Console::SetVerbosity(4); + } +}; ////////////////////////////////////////////////// TEST(Manager, construct) diff --git a/src/Noise_TEST.cc b/src/Noise_TEST.cc index 62094e73..735f3f1c 100644 --- a/src/Noise_TEST.cc +++ b/src/Noise_TEST.cc @@ -19,6 +19,7 @@ #include +#include #include #include "ignition/sensors/Noise.hh" @@ -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) diff --git a/src/Sensor_TEST.cc b/src/Sensor_TEST.cc index 8acd0db0..9b4e7581 100644 --- a/src/Sensor_TEST.cc +++ b/src/Sensor_TEST.cc @@ -16,6 +16,7 @@ */ #include +#include #include #include @@ -33,6 +34,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) { diff --git a/test/integration/air_pressure_plugin.cc b/test/integration/air_pressure_plugin.cc index d42c1a43..b3e698fc 100644 --- a/test/integration/air_pressure_plugin.cc +++ b/test/integration/air_pressure_plugin.cc @@ -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); + } }; ///////////////////////////////////////////////// @@ -128,7 +134,7 @@ TEST_F(AirPressureSensorTest, CreateAirPressure) sf.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); std::unique_ptr sensor = sf.CreateSensor(airPressureSdf); - EXPECT_TRUE(sensor != nullptr); + ASSERT_NE(nullptr, sensor); EXPECT_EQ(name, sensor->Name()); EXPECT_EQ(topic, sensor->Topic()); @@ -137,7 +143,7 @@ TEST_F(AirPressureSensorTest, CreateAirPressure) std::unique_ptr sensorNoise = sf.CreateSensor( airPressureSdfNoise); - EXPECT_TRUE(sensorNoise != nullptr); + ASSERT_NE(nullptr, sensorNoise); EXPECT_EQ(name, sensorNoise->Name()); EXPECT_EQ(topicNoise, sensorNoise->Topic()); @@ -174,7 +180,7 @@ TEST_F(AirPressureSensorTest, SensorReadings) dynamic_cast(s.release())); // Make sure the above dynamic cast worked. - EXPECT_TRUE(sensor != nullptr); + ASSERT_NE(nullptr, sensor); std::unique_ptr sNoise = sf.CreateSensor(airPressureSdfNoise); @@ -182,7 +188,7 @@ TEST_F(AirPressureSensorTest, SensorReadings) dynamic_cast(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()); diff --git a/test/integration/altimeter_plugin.cc b/test/integration/altimeter_plugin.cc index e0788604..7bee0391 100644 --- a/test/integration/altimeter_plugin.cc +++ b/test/integration/altimeter_plugin.cc @@ -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); + } }; ///////////////////////////////////////////////// @@ -135,7 +141,7 @@ TEST_F(AltimeterSensorTest, CreateAltimeter) sf.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); std::unique_ptr sensor = sf.CreateSensor(altimeterSdf); - EXPECT_TRUE(sensor != nullptr); + ASSERT_NE(nullptr, sensor); EXPECT_EQ(name, sensor->Name()); EXPECT_EQ(topic, sensor->Topic()); @@ -143,7 +149,7 @@ TEST_F(AltimeterSensorTest, CreateAltimeter) std::unique_ptr sensorNoise = sf.CreateSensor(altimeterSdfNoise); - EXPECT_TRUE(sensorNoise != nullptr); + ASSERT_NE(nullptr, sensorNoise); EXPECT_EQ(name, sensorNoise->Name()); EXPECT_EQ(topicNoise, sensorNoise->Topic()); @@ -180,7 +186,7 @@ TEST_F(AltimeterSensorTest, SensorReadings) dynamic_cast(s.release())); // Make sure the above dynamic cast worked. - EXPECT_TRUE(sensor != nullptr); + ASSERT_NE(nullptr, sensor); std::unique_ptr sNoise = sf.CreateSensor(altimeterSdfNoise); @@ -188,7 +194,7 @@ TEST_F(AltimeterSensorTest, SensorReadings) dynamic_cast(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()); diff --git a/test/integration/camera_plugin.cc b/test/integration/camera_plugin.cc index d9724a0d..3b1932f7 100644 --- a/test/integration/camera_plugin.cc +++ b/test/integration/camera_plugin.cc @@ -88,6 +88,7 @@ void CameraSensorTest::ImagesWithBuiltinSDF(const std::string &_renderEngine) ignition::rendering::unloadEngine(engine->Name()); } +////////////////////////////////////////////////// TEST_P(CameraSensorTest, ImagesWithBuiltinSDF) { ImagesWithBuiltinSDF(GetParam()); @@ -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(); } diff --git a/test/integration/depth_camera_plugin.cc b/test/integration/depth_camera_plugin.cc index fded2bcb..049c2aec 100644 --- a/test/integration/depth_camera_plugin.cc +++ b/test/integration/depth_camera_plugin.cc @@ -477,6 +477,7 @@ void DepthCameraSensorTest::ImagesWithBuiltinSDF( ignition::rendering::unloadEngine(engine->Name()); } +////////////////////////////////////////////////// TEST_P(DepthCameraSensorTest, ImagesWithBuiltinSDF) { ImagesWithBuiltinSDF(GetParam()); @@ -488,6 +489,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(); } diff --git a/test/integration/gpu_lidar_sensor_plugin.cc b/test/integration/gpu_lidar_sensor_plugin.cc index c4c0d8e6..3eab0df6 100644 --- a/test/integration/gpu_lidar_sensor_plugin.cc +++ b/test/integration/gpu_lidar_sensor_plugin.cc @@ -198,7 +198,7 @@ void GpuLidarSensorTest::CreateGpuLidar(const std::string &_renderEngine) mgr.CreateSensor(lidarSdf); sensor->SetParent(parent); // Make sure the above dynamic cast worked. - EXPECT_TRUE(sensor != nullptr); + ASSERT_NE(nullptr, sensor); sensor->SetScene(scene); // Set a callback on the lidar sensor to get a scan @@ -324,7 +324,7 @@ void GpuLidarSensorTest::DetectBox(const std::string &_renderEngine) ignition::sensors::GpuLidarSensor *sensor = mgr.CreateSensor(lidarSdf); // Make sure the above dynamic cast worked. - EXPECT_TRUE(sensor != nullptr); + ASSERT_NE(nullptr, sensor); sensor->SetParent(parent); sensor->SetScene(scene); @@ -473,8 +473,8 @@ void GpuLidarSensorTest::TestThreeBoxes(const std::string &_renderEngine) mgr.CreateSensor(lidarSdf2); // Make sure the above dynamic cast worked. - EXPECT_TRUE(sensor1 != nullptr); - EXPECT_TRUE(sensor2 != nullptr); + ASSERT_NE(nullptr, sensor1); + ASSERT_NE(nullptr, sensor2); sensor1->SetScene(scene); sensor2->SetScene(scene); @@ -615,7 +615,7 @@ void GpuLidarSensorTest::VerticalLidar(const std::string &_renderEngine) mgr.CreateSensor(lidarSdf); // Make sure the above dynamic cast worked. - EXPECT_TRUE(sensor != nullptr); + ASSERT_NE(nullptr, sensor); sensor->SetScene(scene); // Update sensor @@ -737,8 +737,8 @@ void GpuLidarSensorTest::ManualUpdate(const std::string &_renderEngine) mgr.CreateSensor(lidarSdf2); // Make sure the above dynamic cast worked. - EXPECT_TRUE(sensor1 != nullptr); - EXPECT_TRUE(sensor2 != nullptr); + ASSERT_NE(nullptr, sensor1); + ASSERT_NE(nullptr, sensor2); sensor1->SetScene(scene); sensor2->SetScene(scene); @@ -875,31 +875,37 @@ void GpuLidarSensorTest::Topic(const std::string &_renderEngine) } } +///////////////////////////////////////////////// TEST_P(GpuLidarSensorTest, CreateGpuLidar) { CreateGpuLidar(GetParam()); } +///////////////////////////////////////////////// TEST_P(GpuLidarSensorTest, DetectBox) { DetectBox(GetParam()); } +///////////////////////////////////////////////// TEST_P(GpuLidarSensorTest, TestThreeBoxes) { TestThreeBoxes(GetParam()); } +///////////////////////////////////////////////// TEST_P(GpuLidarSensorTest, VerticalLidar) { VerticalLidar(GetParam()); } +///////////////////////////////////////////////// TEST_P(GpuLidarSensorTest, ManualUpdate) { ManualUpdate(GetParam()); } +///////////////////////////////////////////////// TEST_P(GpuLidarSensorTest, Topic) { Topic(GetParam()); @@ -910,6 +916,7 @@ INSTANTIATE_TEST_CASE_P(GpuLidarSensor, GpuLidarSensorTest, int main(int argc, char **argv) { + ignition::common::Console::SetVerbosity(4); ::testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } diff --git a/test/integration/imu_plugin.cc b/test/integration/imu_plugin.cc index d7c52794..914f9401 100644 --- a/test/integration/imu_plugin.cc +++ b/test/integration/imu_plugin.cc @@ -57,8 +57,14 @@ sdf::ElementPtr ImuToSdf(const std::string &_name, ->GetElement("sensor"); } +/// \brief Test IMU sensor class ImuSensorTest: public testing::Test { + // Documentation inherited + protected: void SetUp() override + { + ignition::common::Console::SetVerbosity(4); + } }; ///////////////////////////////////////////////// @@ -82,7 +88,7 @@ TEST_F(ImuSensorTest, CreateImu) sf.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); std::unique_ptr sensor = sf.CreateSensor(imuSdf); - EXPECT_TRUE(sensor != nullptr); + ASSERT_NE(nullptr, sensor); EXPECT_EQ(name, sensor->Name()); EXPECT_EQ(topic, sensor->Topic()); @@ -115,7 +121,7 @@ TEST_F(ImuSensorTest, SensorReadings) dynamic_cast(s.release())); // Make sure the above dynamic cast worked. - EXPECT_TRUE(sensor != nullptr); + ASSERT_NE(nullptr, sensor); // subscribe to the topic WaitForMessageTestHelper msgHelper(topic); diff --git a/test/integration/logical_camera_plugin.cc b/test/integration/logical_camera_plugin.cc index 403367fb..6298e7b2 100644 --- a/test/integration/logical_camera_plugin.cc +++ b/test/integration/logical_camera_plugin.cc @@ -78,8 +78,14 @@ sdf::ElementPtr LogicalCameraToSdf(const std::string &_name, ->GetElement("sensor"); } +/// \brief Test logical camera sensor class LogicalCameraSensorTest: public testing::Test { + // Documentation inherited + protected: void SetUp() override + { + ignition::common::Console::SetVerbosity(4); + } }; ///////////////////////////////////////////////// @@ -108,7 +114,7 @@ TEST_F(LogicalCameraSensorTest, CreateLogicalCamera) sf.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); std::unique_ptr sensor = sf.CreateSensor(logicalCameraSdf); - EXPECT_TRUE(sensor != nullptr); + ASSERT_NE(nullptr, sensor); EXPECT_EQ(name, sensor->Name()); EXPECT_EQ(topic, sensor->Topic()); @@ -151,7 +157,7 @@ TEST_F(LogicalCameraSensorTest, DetectBox) dynamic_cast(s.release())); // Make sure the above dynamic cast worked. - EXPECT_TRUE(sensor != nullptr); + ASSERT_NE(nullptr, sensor); // verify initial image auto img = sensor->Image(); diff --git a/test/integration/magnetometer_plugin.cc b/test/integration/magnetometer_plugin.cc index 694448b3..6529e3c0 100644 --- a/test/integration/magnetometer_plugin.cc +++ b/test/integration/magnetometer_plugin.cc @@ -112,9 +112,14 @@ sdf::ElementPtr MagnetometerToSdfWithNoise(const std::string &_name, ->GetElement("sensor"); } - +/// \brief Test magnetometer sensor class MagnetometerSensorTest: public testing::Test { + // Documentation inherited + protected: void SetUp() override + { + ignition::common::Console::SetVerbosity(4); + } }; ///////////////////////////////////////////////// @@ -142,12 +147,12 @@ TEST_F(MagnetometerSensorTest, CreateMagnetometer) sf.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); std::unique_ptr sensor = sf.CreateSensor(magnetometerSdf); - EXPECT_TRUE(sensor != nullptr); + ASSERT_NE(nullptr, sensor); std::unique_ptr sensorNoise = sf.CreateSensor( magnetometerNoiseSdf); - EXPECT_TRUE(sensorNoise != nullptr); + ASSERT_NE(nullptr, sensorNoise); EXPECT_EQ(name, sensor->Name()); EXPECT_EQ(name, sensorNoise->Name()); @@ -191,8 +196,8 @@ TEST_F(MagnetometerSensorTest, SensorReadings) dynamic_cast(sNoise.release())); // Make sure the above dynamic cast worked. - EXPECT_TRUE(sensor != nullptr); - EXPECT_TRUE(sensorNoise != nullptr); + ASSERT_NE(nullptr, sensor); + ASSERT_NE(nullptr, sensorNoise); // subscribe to the topic WaitForMessageTestHelper msgHelper(topic); diff --git a/test/integration/rgbd_camera_plugin.cc b/test/integration/rgbd_camera_plugin.cc index 98de0fca..15a0e5e9 100644 --- a/test/integration/rgbd_camera_plugin.cc +++ b/test/integration/rgbd_camera_plugin.cc @@ -714,6 +714,7 @@ void RgbdCameraSensorTest::ImagesWithBuiltinSDF( ignition::rendering::unloadEngine(engine->Name()); } +////////////////////////////////////////////////// TEST_P(RgbdCameraSensorTest, ImagesWithBuiltinSDF) { ImagesWithBuiltinSDF(GetParam()); @@ -725,6 +726,7 @@ INSTANTIATE_TEST_CASE_P(RgbdCameraSensor, RgbdCameraSensorTest, ////////////////////////////////////////////////// int main(int argc, char **argv) { + ignition::common::Console::SetVerbosity(4); ::testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } diff --git a/test/integration/thermal_camera_plugin.cc b/test/integration/thermal_camera_plugin.cc index c4455b76..3455df4a 100644 --- a/test/integration/thermal_camera_plugin.cc +++ b/test/integration/thermal_camera_plugin.cc @@ -315,6 +315,7 @@ void ThermalCameraSensorTest::ImagesWithBuiltinSDF( ignition::rendering::unloadEngine(engine->Name()); } +////////////////////////////////////////////////// TEST_P(ThermalCameraSensorTest, ImagesWithBuiltinSDF) { ImagesWithBuiltinSDF(GetParam()); @@ -326,6 +327,7 @@ INSTANTIATE_TEST_CASE_P(ThermalCameraSensor, ThermalCameraSensorTest, ////////////////////////////////////////////////// int main(int argc, char **argv) { + ignition::common::Console::SetVerbosity(4); ::testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } From ea140143e86dbe04a80d8571e06f92d84a4a93f8 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Tue, 3 Nov 2020 10:36:16 -0800 Subject: [PATCH 2/2] some more info in the error message Signed-off-by: Louise Poubel --- include/ignition/sensors/Manager.hh | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/include/ignition/sensors/Manager.hh b/include/ignition/sensors/Manager.hh index 01b8fa50..c5ef9ada 100644 --- a/include/ignition/sensors/Manager.hh +++ b/include/ignition/sensors/Manager.hh @@ -123,13 +123,18 @@ namespace ignition { T *result = dynamic_cast(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("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("type") << "]\n"; return nullptr; }