Skip to content

Commit

Permalink
Remove deprecations: tock (#141)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <louise@openrobotics.org>
  • Loading branch information
chapulina authored Jun 25, 2021
1 parent b7097d1 commit 53c87ea
Show file tree
Hide file tree
Showing 30 changed files with 0 additions and 255 deletions.
7 changes: 0 additions & 7 deletions include/ignition/sensors/AirPressureSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@
#include <sdf/sdf.hh>

#include <ignition/common/SuppressWarning.hh>
#include <ignition/common/Time.hh>

#include <ignition/sensors/config.hh>
#include <ignition/sensors/air_pressure/Export.hh>
Expand Down Expand Up @@ -65,12 +64,6 @@ namespace ignition
/// \return True on success
public: virtual bool Init() override;

/// \brief Update the sensor and generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
public: virtual bool IGN_DEPRECATED(4) Update(
const ignition::common::Time &_now) override;

/// \brief Update the sensor and generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
Expand Down
7 changes: 0 additions & 7 deletions include/ignition/sensors/AltimeterSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@
#include <sdf/sdf.hh>

#include <ignition/common/SuppressWarning.hh>
#include <ignition/common/Time.hh>

#include <ignition/sensors/config.hh>
#include <ignition/sensors/altimeter/Export.hh>
Expand Down Expand Up @@ -65,12 +64,6 @@ namespace ignition
/// \return True on success
public: virtual bool Init() override;

/// \brief Update the sensor and generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
public: virtual bool IGN_DEPRECATED(4) Update(
const ignition::common::Time &_now) override;

/// \brief Update the sensor and generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
Expand Down
12 changes: 0 additions & 12 deletions include/ignition/sensors/CameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@

#include <ignition/common/PluginMacros.hh>
#include <ignition/common/SuppressWarning.hh>
#include <ignition/common/Time.hh>

#ifdef _WIN32
#pragma warning(push)
Expand Down Expand Up @@ -92,12 +91,6 @@ namespace ignition
/// \return True on success
public: virtual bool Init() override;

/// \brief Update the sensor and generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
public: virtual bool IGN_DEPRECATED(4) Update(
const ignition::common::Time &_now) override;

/// \brief Force the sensor to generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
Expand Down Expand Up @@ -162,11 +155,6 @@ namespace ignition
/// information.
protected: void PopulateInfo(const sdf::Camera *_cameraSdf);

/// \brief Publish camera info message.
/// \param[in] _now The current time
protected: void IGN_DEPRECATED(4) PublishInfo(
const ignition::common::Time &_now);

/// \brief Publish camera info message.
/// \param[in] _now The current time
protected: void PublishInfo(
Expand Down
7 changes: 0 additions & 7 deletions include/ignition/sensors/DepthCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@
#include <ignition/common/Event.hh>
#include <ignition/common/PluginMacros.hh>
#include <ignition/common/SuppressWarning.hh>
#include <ignition/common/Time.hh>

#ifdef _WIN32
#pragma warning(push)
Expand Down Expand Up @@ -93,12 +92,6 @@ namespace ignition
/// \return True on success
public: virtual bool Init() override;

/// \brief Force the sensor to generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
public: virtual bool IGN_DEPRECATED(4) Update(
const ignition::common::Time &_now) override;

/// \brief Force the sensor to generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
Expand Down
6 changes: 0 additions & 6 deletions include/ignition/sensors/GpuLidarSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -66,12 +66,6 @@ namespace ignition
/// \brief destructor
public: virtual ~GpuLidarSensor();

/// \brief Force the sensor to generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
public: virtual bool IGN_DEPRECATED(4) Update(
const ignition::common::Time &_now) override;

/// \brief Force the sensor to generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
Expand Down
7 changes: 0 additions & 7 deletions include/ignition/sensors/ImuSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@
#include <sdf/sdf.hh>

#include <ignition/common/SuppressWarning.hh>
#include <ignition/common/Time.hh>
#include <ignition/math/Pose3.hh>

#include <ignition/sensors/config.hh>
Expand Down Expand Up @@ -66,12 +65,6 @@ namespace ignition
/// \return True on success
public: virtual bool Init() override;

/// \brief Update the sensor and generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
public: virtual bool IGN_DEPRECATED(4) Update(
const ignition::common::Time &_now) override;

/// \brief Update the sensor and generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
Expand Down
12 changes: 0 additions & 12 deletions include/ignition/sensors/Lidar.hh
Original file line number Diff line number Diff line change
Expand Up @@ -54,24 +54,12 @@ namespace ignition
/// \brief destructor
public: virtual ~Lidar();

/// \brief Update the sensor and generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
public: virtual bool IGN_DEPRECATED(4) Update(
const ignition::common::Time &_now) override;

/// \brief Force the sensor to generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
public: virtual bool Update(
const std::chrono::steady_clock::duration &_now) override;

/// \brief Publish LaserScan message
/// \param[in] _now The current time
/// \return true if the update was successfull
public: virtual bool IGN_DEPRECATED(4) PublishLidarScan(
const ignition::common::Time &_now);

/// \brief Apply noise to the laser buffer, if noise has been
/// configured. This should be called before PublishLidarScan if you
/// want the scan data to contain noise.
Expand Down
7 changes: 0 additions & 7 deletions include/ignition/sensors/LogicalCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@

#include <ignition/common/PluginMacros.hh>
#include <ignition/common/SuppressWarning.hh>
#include <ignition/common/Time.hh>

#include <ignition/math/Angle.hh>

Expand Down Expand Up @@ -77,12 +76,6 @@ namespace ignition
/// \return True on success
public: virtual bool Init() override;

/// \brief Update the sensor and generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
public: virtual bool IGN_DEPRECATED(4) Update(
const ignition::common::Time &_now) override;

/// \brief Force the sensor to generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
Expand Down
7 changes: 0 additions & 7 deletions include/ignition/sensors/MagnetometerSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@
#include <sdf/sdf.hh>

#include <ignition/common/SuppressWarning.hh>
#include <ignition/common/Time.hh>
#include <ignition/math/Pose3.hh>

#include <ignition/sensors/config.hh>
Expand Down Expand Up @@ -66,12 +65,6 @@ namespace ignition
/// \return True on success
public: virtual bool Init() override;

/// \brief Update the sensor and generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
public: virtual bool IGN_DEPRECATED(4) Update(
const ignition::common::Time &_now) override;

/// \brief Update the sensor and generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
Expand Down
8 changes: 0 additions & 8 deletions include/ignition/sensors/Manager.hh
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@
#include <vector>
#include <sdf/sdf.hh>
#include <ignition/common/SuppressWarning.hh>
#include <ignition/common/Time.hh>
#include <ignition/common/Console.hh>
#include <ignition/sensors/config.hh>
#include <ignition/sensors/Export.hh>
Expand Down Expand Up @@ -190,13 +189,6 @@ namespace ignition
/// \return True if the sensor exists and removed.
public: bool Remove(const ignition::sensors::SensorId _id);

/// \brief Run the sensor generation one step.
/// \param _time: The current simulated time
/// \param _force: If true, all sensors are forced to update. Otherwise
/// a sensor will update based on it's Hz rate.
public: void IGN_DEPRECATED(4) RunOnce(
const ignition::common::Time &_time, bool _force = false);

/// \brief Run the sensor generation one step.
/// \param _time: The current simulated time
/// \param _force: If true, all sensors are forced to update. Otherwise
Expand Down
7 changes: 0 additions & 7 deletions include/ignition/sensors/RgbdCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@
#include <sdf/sdf.hh>

#include <ignition/common/SuppressWarning.hh>
#include <ignition/common/Time.hh>

#include "ignition/sensors/CameraSensor.hh"
#include "ignition/sensors/config.hh"
Expand Down Expand Up @@ -67,12 +66,6 @@ namespace ignition
/// \return True on success
public: virtual bool Init() override;

/// \brief Force the sensor to generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
public: virtual bool IGN_DEPRECATED(4) Update(
const ignition::common::Time &_now) override;

/// \brief Force the sensor to generate data
/// \param[in] _now The current time
/// \return true if the update was successful
Expand Down
38 changes: 0 additions & 38 deletions include/ignition/sensors/Sensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@
#include <string>

#include <ignition/common/SuppressWarning.hh>
#include <ignition/common/Time.hh>
#include <ignition/math/Pose3.hh>
#include <ignition/sensors/config.hh>
#include <ignition/sensors/Export.hh>
Expand Down Expand Up @@ -80,22 +79,6 @@ namespace ignition
/// a seek backward in a log file.
public: virtual bool Init();

/// \brief Force the sensor to generate data
///
/// This method must be overridden by sensors. Subclasses should not
/// not make a decision about whether or not they need to update. The
/// Sensor class will make sure Update() is called at the correct time.
///
/// If a subclass wants to have a variable update rate it should call
/// SetUpdateRate().
///
/// A subclass should return false if there was an error while updating
/// \param[in] _now The current time
/// \return true if the update was successfull
/// \sa SetUpdateRate()
public:
virtual bool IGN_DEPRECATED(4) Update(const common::Time &_now) = 0;

/// \brief Force the sensor to generate data
///
/// This method must be overridden by sensors. Subclasses should not
Expand All @@ -112,9 +95,6 @@ namespace ignition
public: virtual bool Update(
const std::chrono::steady_clock::duration &_now) = 0;

/// \brief Return the next time the sensor will generate data
public: ignition::common::Time IGN_DEPRECATED(4) NextUpdateTime() const;

/// \brief Return the next time the sensor will generate data
public: std::chrono::steady_clock::duration NextDataUpdateTime() const;

Expand All @@ -131,24 +111,6 @@ namespace ignition
/// function returned true.
/// False otherwise.
/// \remarks If forced the NextUpdateTime() will be unchanged.
/// \sa virtual bool Update(const common::Time &_name) = 0
public: bool IGN_DEPRECATED(4)
Update(const ignition::common::Time &_now, const bool _force);

/// \brief Update the sensor.
///
/// This is called by the manager, and is responsible for determining
/// if this sensor needs to generate data at this time. If so, the
/// subclasses' Update() method will be called.
/// \param[in] _now The current time
/// \param[in] _force Force the update to happen even if it's not time
/// \return True if the update was triggered (_force was true or _now
/// >= next_update_time) and the sensor's
/// bool Sensor::Update(std::chrono::steady_clock::time_point)
/// function returned true.
/// False otherwise.
/// \remarks If forced the NextUpdateTime() will be unchanged.
/// \sa virtual bool Update(const common::Time &_name) = 0
public: bool Update(
const std::chrono::steady_clock::duration &_now, const bool _force);

Expand Down
7 changes: 0 additions & 7 deletions include/ignition/sensors/ThermalCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@
#include <ignition/common/Event.hh>
#include <ignition/common/PluginMacros.hh>
#include <ignition/common/SuppressWarning.hh>
#include <ignition/common/Time.hh>

#ifdef _WIN32
#pragma warning(push)
Expand Down Expand Up @@ -93,12 +92,6 @@ namespace ignition
/// \return True on success
public: virtual bool Init() override;

/// \brief Force the sensor to generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
public: virtual bool IGN_DEPRECATED(4) Update(
const ignition::common::Time &_now) override;

/// \brief Force the sensor to generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
Expand Down
7 changes: 0 additions & 7 deletions src/AirPressureSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -141,13 +141,6 @@ bool AirPressureSensor::Load(sdf::ElementPtr _sdf)
return this->Load(sdfSensor);
}

//////////////////////////////////////////////////
bool AirPressureSensor::Update(
const ignition::common::Time &_now)
{
return this->Update(math::secNsecToDuration(_now.sec, _now.nsec));
}

//////////////////////////////////////////////////
bool AirPressureSensor::Update(
const std::chrono::steady_clock::duration &_now)
Expand Down
7 changes: 0 additions & 7 deletions src/AltimeterSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -129,13 +129,6 @@ bool AltimeterSensor::Load(sdf::ElementPtr _sdf)
return this->Load(sdfSensor);
}

//////////////////////////////////////////////////
bool AltimeterSensor::Update(
const ignition::common::Time &_now)
{
return this->Update(math::secNsecToDuration(_now.sec, _now.nsec));
}

//////////////////////////////////////////////////
bool AltimeterSensor::Update(const std::chrono::steady_clock::duration &_now)
{
Expand Down
3 changes: 0 additions & 3 deletions src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,6 @@ endif()
# Create the library target.
ign_create_core_library(SOURCES ${sources} CXX_STANDARD 14)

# todo(anyone) dependency on rendering has been moved to its own component
# and relevant functions are deprecated in ign-sensors 2. We can remove linking
# against ign-rendering from the core lib in ign-sensors 3
target_link_libraries(${PROJECT_LIBRARY_TARGET_NAME}
PUBLIC
ignition-math${IGN_MATH_VER}::ignition-math${IGN_MATH_VER}
Expand Down
14 changes: 0 additions & 14 deletions src/CameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -312,13 +312,6 @@ void CameraSensor::SetScene(ignition::rendering::ScenePtr _scene)
}
}

//////////////////////////////////////////////////
bool CameraSensor::Update(
const ignition::common::Time &_now)
{
return this->Update(math::secNsecToDuration(_now.sec, _now.nsec));
}

//////////////////////////////////////////////////
bool CameraSensor::Update(const std::chrono::steady_clock::duration &_now)
{
Expand Down Expand Up @@ -545,13 +538,6 @@ void CameraSensor::PublishInfo(
this->dataPtr->infoPub.Publish(this->dataPtr->infoMsg);
}

//////////////////////////////////////////////////
void CameraSensor::PublishInfo(
const ignition::common::Time &_now)
{
this->PublishInfo(math::secNsecToDuration(_now.sec, _now.nsec));
}

//////////////////////////////////////////////////
void CameraSensor::PopulateInfo(const sdf::Camera *_cameraSdf)
{
Expand Down
Loading

0 comments on commit 53c87ea

Please sign in to comment.