Skip to content

Commit

Permalink
Let derived sensors call Sensor::Update (#187)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina authored Jan 12, 2022
1 parent 53bcc7f commit 994d191
Show file tree
Hide file tree
Showing 13 changed files with 20 additions and 6 deletions.
2 changes: 2 additions & 0 deletions include/ignition/sensors/AirPressureSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 2 additions & 0 deletions include/ignition/sensors/AltimeterSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 2 additions & 0 deletions include/ignition/sensors/CameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 2 additions & 0 deletions include/ignition/sensors/ForceTorqueSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 2 additions & 0 deletions include/ignition/sensors/ImuSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 2 additions & 0 deletions include/ignition/sensors/LogicalCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 2 additions & 0 deletions include/ignition/sensors/MagnetometerSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion test/integration/air_pressure.cc
Original file line number Diff line number Diff line change
Expand Up @@ -209,7 +209,7 @@ TEST_F(AirPressureSensorTest, SensorReadings)
WaitForMessageTestHelper<ignition::msgs::FluidPressure>
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());
Expand Down
2 changes: 1 addition & 1 deletion test/integration/altimeter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -235,7 +235,7 @@ TEST_F(AltimeterSensorTest, SensorReadings)
WaitForMessageTestHelper<ignition::msgs::Altimeter>
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());
Expand Down
2 changes: 1 addition & 1 deletion test/integration/force_torque.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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());
Expand Down
2 changes: 1 addition & 1 deletion test/integration/imu.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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());
Expand Down
2 changes: 1 addition & 1 deletion test/integration/logical_camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down
2 changes: 1 addition & 1 deletion test/integration/magnetometer.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit 994d191

Please sign in to comment.