From 26f3aabf39f4a12da12040cff75f4f62f219d35a Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Tue, 11 Jan 2022 15:36:41 -0800 Subject: [PATCH 1/2] Let derived sensors call Sensor::Update Signed-off-by: Louise Poubel --- include/ignition/sensors/AirPressureSensor.hh | 2 ++ include/ignition/sensors/AltimeterSensor.hh | 2 ++ include/ignition/sensors/CameraSensor.hh | 2 ++ include/ignition/sensors/ForceTorqueSensor.hh | 2 ++ include/ignition/sensors/ImuSensor.hh | 2 ++ include/ignition/sensors/LogicalCameraSensor.hh | 2 ++ include/ignition/sensors/MagnetometerSensor.hh | 2 ++ test/integration/air_pressure.cc | 2 +- test/integration/altimeter.cc | 2 +- test/integration/force_torque.cc | 2 +- test/integration/imu.cc | 2 +- test/integration/logical_camera.cc | 2 +- test/integration/magnetometer.cc | 2 +- 13 files changed, 20 insertions(+), 6 deletions(-) diff --git a/include/ignition/sensors/AirPressureSensor.hh b/include/ignition/sensors/AirPressureSensor.hh index 373ddd45..3b8c7dbf 100644 --- a/include/ignition/sensors/AirPressureSensor.hh +++ b/include/ignition/sensors/AirPressureSensor.hh @@ -64,6 +64,8 @@ namespace ignition /// \return True on success public: virtual bool Init() override; + using Sensor::Update; + /// \brief Update the sensor and generate data /// \param[in] _now The current time /// \return true if the update was successfull diff --git a/include/ignition/sensors/AltimeterSensor.hh b/include/ignition/sensors/AltimeterSensor.hh index b22e95f5..bfe895b2 100644 --- a/include/ignition/sensors/AltimeterSensor.hh +++ b/include/ignition/sensors/AltimeterSensor.hh @@ -64,6 +64,8 @@ namespace ignition /// \return True on success public: virtual bool Init() override; + using Sensor::Update; + /// \brief Update the sensor and generate data /// \param[in] _now The current time /// \return true if the update was successfull diff --git a/include/ignition/sensors/CameraSensor.hh b/include/ignition/sensors/CameraSensor.hh index ca3ab22f..9f727382 100644 --- a/include/ignition/sensors/CameraSensor.hh +++ b/include/ignition/sensors/CameraSensor.hh @@ -90,6 +90,8 @@ namespace ignition /// \return True on success public: virtual bool Init() override; + using Sensor::Update; + /// \brief Force the sensor to generate data /// \param[in] _now The current time /// \return true if the update was successfull diff --git a/include/ignition/sensors/ForceTorqueSensor.hh b/include/ignition/sensors/ForceTorqueSensor.hh index 5ff0f439..0a1f915a 100644 --- a/include/ignition/sensors/ForceTorqueSensor.hh +++ b/include/ignition/sensors/ForceTorqueSensor.hh @@ -67,6 +67,8 @@ namespace ignition /// \return True on success public: virtual bool Init() override; + using Sensor::Update; + /// \brief Update the sensor and generate data /// \param[in] _now The current time /// \return true if the update was successfull diff --git a/include/ignition/sensors/ImuSensor.hh b/include/ignition/sensors/ImuSensor.hh index a0212b72..84a92402 100644 --- a/include/ignition/sensors/ImuSensor.hh +++ b/include/ignition/sensors/ImuSensor.hh @@ -65,6 +65,8 @@ namespace ignition /// \return True on success public: virtual bool Init() override; + using Sensor::Update; + /// \brief Update the sensor and generate data /// \param[in] _now The current time /// \return true if the update was successfull diff --git a/include/ignition/sensors/LogicalCameraSensor.hh b/include/ignition/sensors/LogicalCameraSensor.hh index b8eb8bac..bb17156d 100644 --- a/include/ignition/sensors/LogicalCameraSensor.hh +++ b/include/ignition/sensors/LogicalCameraSensor.hh @@ -75,6 +75,8 @@ namespace ignition /// \return True on success public: virtual bool Init() override; + using Sensor::Update; + /// \brief Force the sensor to generate data /// \param[in] _now The current time /// \return true if the update was successfull diff --git a/include/ignition/sensors/MagnetometerSensor.hh b/include/ignition/sensors/MagnetometerSensor.hh index c8b97a51..35cfe94c 100644 --- a/include/ignition/sensors/MagnetometerSensor.hh +++ b/include/ignition/sensors/MagnetometerSensor.hh @@ -65,6 +65,8 @@ namespace ignition /// \return True on success public: virtual bool Init() override; + using Sensor::Update; + /// \brief Update the sensor and generate data /// \param[in] _now The current time /// \return true if the update was successfull diff --git a/test/integration/air_pressure.cc b/test/integration/air_pressure.cc index f0670319..5c1a609b 100644 --- a/test/integration/air_pressure.cc +++ b/test/integration/air_pressure.cc @@ -209,7 +209,7 @@ TEST_F(AirPressureSensorTest, SensorReadings) WaitForMessageTestHelper msgHelperNoise(topicNoise); sensorNoise->Update(std::chrono::steady_clock::duration( - std::chrono::seconds(1))); + std::chrono::seconds(1)), false); EXPECT_TRUE(msgHelperNoise.WaitForMessage()) << msgHelperNoise; auto msgNoise = msgHelperNoise.Message(); EXPECT_EQ(1, msg.header().stamp().sec()); diff --git a/test/integration/altimeter.cc b/test/integration/altimeter.cc index f568d185..466b78ba 100644 --- a/test/integration/altimeter.cc +++ b/test/integration/altimeter.cc @@ -235,7 +235,7 @@ TEST_F(AltimeterSensorTest, SensorReadings) WaitForMessageTestHelper msgHelperNoise(topicNoise); sensorNoise->Update(std::chrono::steady_clock::duration( - std::chrono::seconds(1))); + std::chrono::seconds(1)), false); EXPECT_TRUE(msgHelperNoise.WaitForMessage()) << msgHelperNoise; auto msgNoise = msgHelperNoise.Message(); EXPECT_EQ(1, msg.header().stamp().sec()); diff --git a/test/integration/force_torque.cc b/test/integration/force_torque.cc index b28b3ebf..4060f15f 100644 --- a/test/integration/force_torque.cc +++ b/test/integration/force_torque.cc @@ -238,7 +238,7 @@ TEST_P(ForceTorqueSensorTest, SensorReadings) sensor->SetRotationParentInSensor(rotParentInSensor); EXPECT_EQ(rotParentInSensor, sensor->RotationParentInSensor()); - sensor->Update(dt); + sensor->Update(dt, false); EXPECT_TRUE(msgHelper.WaitForMessage()) << msgHelper; auto msg = msgHelper.Message(); EXPECT_EQ(1, msg.header().stamp().sec()); diff --git a/test/integration/imu.cc b/test/integration/imu.cc index 2b630443..139c1339 100644 --- a/test/integration/imu.cc +++ b/test/integration/imu.cc @@ -196,7 +196,7 @@ TEST_F(ImuSensorTest, SensorReadings) // update sensor and verify new readings EXPECT_TRUE(sensor->Update(std::chrono::steady_clock::duration( - std::chrono::seconds(2)))); + std::chrono::seconds(2))), false); EXPECT_EQ(orientRef, sensor->OrientationReference()); EXPECT_EQ(gravity, sensor->Gravity()); EXPECT_EQ(angularVel, sensor->AngularVelocity()); diff --git a/test/integration/logical_camera.cc b/test/integration/logical_camera.cc index d4ff2d3e..8bea1c2e 100644 --- a/test/integration/logical_camera.cc +++ b/test/integration/logical_camera.cc @@ -192,7 +192,7 @@ TEST_F(LogicalCameraSensorTest, DetectBox) sensor->SetModelPoses(std::move(modelPoses2)); // update - sensor->Update(std::chrono::steady_clock::duration::zero()); + sensor->Update(std::chrono::steady_clock::duration::zero(), false); // verify box is not in the image img = sensor->Image(); diff --git a/test/integration/magnetometer.cc b/test/integration/magnetometer.cc index 4ba223f8..4253ff16 100644 --- a/test/integration/magnetometer.cc +++ b/test/integration/magnetometer.cc @@ -241,7 +241,7 @@ TEST_F(MagnetometerSensorTest, SensorReadings) EXPECT_EQ(worldField, sensor->MagneticField()); EXPECT_TRUE(sensorNoise->Update(std::chrono::steady_clock::duration( - std::chrono::seconds(1)))); + std::chrono::seconds(1))), false); EXPECT_EQ(poseNoise, sensorNoise->WorldPose()); EXPECT_EQ(worldFieldNoise, sensorNoise->WorldMagneticField()); // There should be noise in the MagneticField From 971c1e06b9a3f9b5d08486436214f222f8e25fa1 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Tue, 11 Jan 2022 15:50:43 -0800 Subject: [PATCH 2/2] fix tests Signed-off-by: Louise Poubel --- test/integration/imu.cc | 2 +- test/integration/magnetometer.cc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/test/integration/imu.cc b/test/integration/imu.cc index 139c1339..487b5e4e 100644 --- a/test/integration/imu.cc +++ b/test/integration/imu.cc @@ -196,7 +196,7 @@ TEST_F(ImuSensorTest, SensorReadings) // update sensor and verify new readings EXPECT_TRUE(sensor->Update(std::chrono::steady_clock::duration( - std::chrono::seconds(2))), false); + std::chrono::seconds(2)), false)); EXPECT_EQ(orientRef, sensor->OrientationReference()); EXPECT_EQ(gravity, sensor->Gravity()); EXPECT_EQ(angularVel, sensor->AngularVelocity()); diff --git a/test/integration/magnetometer.cc b/test/integration/magnetometer.cc index 4253ff16..24dc1c17 100644 --- a/test/integration/magnetometer.cc +++ b/test/integration/magnetometer.cc @@ -241,7 +241,7 @@ TEST_F(MagnetometerSensorTest, SensorReadings) EXPECT_EQ(worldField, sensor->MagneticField()); EXPECT_TRUE(sensorNoise->Update(std::chrono::steady_clock::duration( - std::chrono::seconds(1))), false); + std::chrono::seconds(1)), false)); EXPECT_EQ(poseNoise, sensorNoise->WorldPose()); EXPECT_EQ(worldFieldNoise, sensorNoise->WorldMagneticField()); // There should be noise in the MagneticField