diff --git a/include/ignition/sensors/AirPressureSensor.hh b/include/ignition/sensors/AirPressureSensor.hh index 4655944a..373ddd45 100644 --- a/include/ignition/sensors/AirPressureSensor.hh +++ b/include/ignition/sensors/AirPressureSensor.hh @@ -22,7 +22,6 @@ #include #include -#include #include #include @@ -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 diff --git a/include/ignition/sensors/AltimeterSensor.hh b/include/ignition/sensors/AltimeterSensor.hh index 59ec82f7..b22e95f5 100644 --- a/include/ignition/sensors/AltimeterSensor.hh +++ b/include/ignition/sensors/AltimeterSensor.hh @@ -22,7 +22,6 @@ #include #include -#include #include #include @@ -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 diff --git a/include/ignition/sensors/CameraSensor.hh b/include/ignition/sensors/CameraSensor.hh index 53423575..6945b75b 100644 --- a/include/ignition/sensors/CameraSensor.hh +++ b/include/ignition/sensors/CameraSensor.hh @@ -25,7 +25,6 @@ #include #include -#include #ifdef _WIN32 #pragma warning(push) @@ -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 @@ -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( diff --git a/include/ignition/sensors/DepthCameraSensor.hh b/include/ignition/sensors/DepthCameraSensor.hh index 59d6b64e..34e886da 100644 --- a/include/ignition/sensors/DepthCameraSensor.hh +++ b/include/ignition/sensors/DepthCameraSensor.hh @@ -26,7 +26,6 @@ #include #include #include -#include #ifdef _WIN32 #pragma warning(push) @@ -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 diff --git a/include/ignition/sensors/GpuLidarSensor.hh b/include/ignition/sensors/GpuLidarSensor.hh index 8ddfbc19..e3af2dd0 100644 --- a/include/ignition/sensors/GpuLidarSensor.hh +++ b/include/ignition/sensors/GpuLidarSensor.hh @@ -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 diff --git a/include/ignition/sensors/ImuSensor.hh b/include/ignition/sensors/ImuSensor.hh index 51e9f77f..46fba50a 100644 --- a/include/ignition/sensors/ImuSensor.hh +++ b/include/ignition/sensors/ImuSensor.hh @@ -22,7 +22,6 @@ #include #include -#include #include #include @@ -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 diff --git a/include/ignition/sensors/Lidar.hh b/include/ignition/sensors/Lidar.hh index ca10f937..293927c7 100644 --- a/include/ignition/sensors/Lidar.hh +++ b/include/ignition/sensors/Lidar.hh @@ -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. diff --git a/include/ignition/sensors/LogicalCameraSensor.hh b/include/ignition/sensors/LogicalCameraSensor.hh index 338e587f..d7bfa002 100644 --- a/include/ignition/sensors/LogicalCameraSensor.hh +++ b/include/ignition/sensors/LogicalCameraSensor.hh @@ -25,7 +25,6 @@ #include #include -#include #include @@ -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 diff --git a/include/ignition/sensors/MagnetometerSensor.hh b/include/ignition/sensors/MagnetometerSensor.hh index fe0f483b..c8b97a51 100644 --- a/include/ignition/sensors/MagnetometerSensor.hh +++ b/include/ignition/sensors/MagnetometerSensor.hh @@ -22,7 +22,6 @@ #include #include -#include #include #include @@ -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 diff --git a/include/ignition/sensors/Manager.hh b/include/ignition/sensors/Manager.hh index a9e04151..9c989b1f 100644 --- a/include/ignition/sensors/Manager.hh +++ b/include/ignition/sensors/Manager.hh @@ -23,7 +23,6 @@ #include #include #include -#include #include #include #include @@ -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 diff --git a/include/ignition/sensors/RgbdCameraSensor.hh b/include/ignition/sensors/RgbdCameraSensor.hh index 2712396f..91069043 100644 --- a/include/ignition/sensors/RgbdCameraSensor.hh +++ b/include/ignition/sensors/RgbdCameraSensor.hh @@ -22,7 +22,6 @@ #include #include -#include #include "ignition/sensors/CameraSensor.hh" #include "ignition/sensors/config.hh" @@ -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 diff --git a/include/ignition/sensors/Sensor.hh b/include/ignition/sensors/Sensor.hh index b0191a66..4d169599 100644 --- a/include/ignition/sensors/Sensor.hh +++ b/include/ignition/sensors/Sensor.hh @@ -31,7 +31,6 @@ #include #include -#include #include #include #include @@ -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 @@ -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; @@ -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); diff --git a/include/ignition/sensors/ThermalCameraSensor.hh b/include/ignition/sensors/ThermalCameraSensor.hh index fddb2ca9..58f68240 100644 --- a/include/ignition/sensors/ThermalCameraSensor.hh +++ b/include/ignition/sensors/ThermalCameraSensor.hh @@ -26,7 +26,6 @@ #include #include #include -#include #ifdef _WIN32 #pragma warning(push) @@ -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 diff --git a/src/AirPressureSensor.cc b/src/AirPressureSensor.cc index 9982e9e3..f3bed50d 100644 --- a/src/AirPressureSensor.cc +++ b/src/AirPressureSensor.cc @@ -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) diff --git a/src/AltimeterSensor.cc b/src/AltimeterSensor.cc index 6391380c..d051c590 100644 --- a/src/AltimeterSensor.cc +++ b/src/AltimeterSensor.cc @@ -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) { diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 1afdb7c0..bf252e95 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -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} diff --git a/src/CameraSensor.cc b/src/CameraSensor.cc index 846cf34f..4c3c3d27 100644 --- a/src/CameraSensor.cc +++ b/src/CameraSensor.cc @@ -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) { @@ -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) { diff --git a/src/DepthCameraSensor.cc b/src/DepthCameraSensor.cc index 561e7b78..a726a3f7 100644 --- a/src/DepthCameraSensor.cc +++ b/src/DepthCameraSensor.cc @@ -504,12 +504,6 @@ void DepthCameraSensor::SetScene(ignition::rendering::ScenePtr _scene) } } -////////////////////////////////////////////////// -bool DepthCameraSensor::Update(const ignition::common::Time &_now) -{ - return this->Update(math::secNsecToDuration(_now.sec, _now.nsec)); -} - ////////////////////////////////////////////////// bool DepthCameraSensor::Update( const std::chrono::steady_clock::duration &_now) diff --git a/src/GpuLidarSensor.cc b/src/GpuLidarSensor.cc index 8c00698f..5abc5e62 100644 --- a/src/GpuLidarSensor.cc +++ b/src/GpuLidarSensor.cc @@ -214,12 +214,6 @@ bool GpuLidarSensor::CreateLidar() return true; } -////////////////////////////////////////////////// -bool GpuLidarSensor::Update(const ignition::common::Time &_now) -{ - return this->Update(math::secNsecToDuration(_now.sec, _now.nsec)); -} - ////////////////////////////////////////////////// bool GpuLidarSensor::Update(const std::chrono::steady_clock::duration &_now) { diff --git a/src/ImuSensor.cc b/src/ImuSensor.cc index ff31c3e6..b7efff39 100644 --- a/src/ImuSensor.cc +++ b/src/ImuSensor.cc @@ -154,13 +154,6 @@ bool ImuSensor::Load(sdf::ElementPtr _sdf) return this->Load(sdfSensor); } -////////////////////////////////////////////////// -bool ImuSensor::Update( - const ignition::common::Time &_now) -{ - return this->Update(math::secNsecToDuration(_now.sec, _now.nsec)); -} - ////////////////////////////////////////////////// bool ImuSensor::Update(const std::chrono::steady_clock::duration &_now) { diff --git a/src/Lidar.cc b/src/Lidar.cc index c88a0083..c1dd1320 100644 --- a/src/Lidar.cc +++ b/src/Lidar.cc @@ -185,13 +185,6 @@ ignition::common::ConnectionPtr Lidar::ConnectNewLidarFrame( return nullptr; } -////////////////////////////////////////////////// -bool Lidar::Update( - const ignition::common::Time &_now) -{ - return this->Update(math::secNsecToDuration(_now.sec, _now.nsec)); -} - ////////////////////////////////////////////////// bool Lidar::Update(const std::chrono::steady_clock::duration &/*_now*/) { @@ -222,12 +215,6 @@ void Lidar::ApplyNoise() } } -////////////////////////////////////////////////// -bool Lidar::PublishLidarScan(const ignition::common::Time &_now) -{ - return this->PublishLidarScan(math::secNsecToDuration(_now.sec, _now.nsec)); -} - ////////////////////////////////////////////////// bool Lidar::PublishLidarScan(const std::chrono::steady_clock::duration &_now) { diff --git a/src/LogicalCameraSensor.cc b/src/LogicalCameraSensor.cc index 75294581..93c74c3d 100644 --- a/src/LogicalCameraSensor.cc +++ b/src/LogicalCameraSensor.cc @@ -128,13 +128,6 @@ void LogicalCameraSensor::SetModelPoses( this->dataPtr->models = std::move(_models); } -////////////////////////////////////////////////// -bool LogicalCameraSensor::Update( - const ignition::common::Time &_now) -{ - return this->Update(math::secNsecToDuration(_now.sec, _now.nsec)); -} - ////////////////////////////////////////////////// bool LogicalCameraSensor::Update( const std::chrono::steady_clock::duration &_now) diff --git a/src/MagnetometerSensor.cc b/src/MagnetometerSensor.cc index 236b3165..61d93264 100644 --- a/src/MagnetometerSensor.cc +++ b/src/MagnetometerSensor.cc @@ -145,13 +145,6 @@ bool MagnetometerSensor::Load(sdf::ElementPtr _sdf) return this->Load(sdfSensor); } -////////////////////////////////////////////////// -bool MagnetometerSensor::Update( - const ignition::common::Time &_now) -{ - return this->Update(math::secNsecToDuration(_now.sec, _now.nsec)); -} - ////////////////////////////////////////////////// bool MagnetometerSensor::Update( const std::chrono::steady_clock::duration &_now) diff --git a/src/Manager.cc b/src/Manager.cc index 9f337279..518ce950 100644 --- a/src/Manager.cc +++ b/src/Manager.cc @@ -91,12 +91,6 @@ bool Manager::Remove(const ignition::sensors::SensorId _id) return this->dataPtr->sensors.erase(_id) > 0; } -////////////////////////////////////////////////// -void Manager::RunOnce(const ignition::common::Time &_time, bool _force) -{ - this->RunOnce(math::secNsecToDuration(_time.sec, _time.nsec), _force); -} - ////////////////////////////////////////////////// void Manager::RunOnce( const std::chrono::steady_clock::duration &_time, bool _force) diff --git a/src/RgbdCameraSensor.cc b/src/RgbdCameraSensor.cc index 90389d8b..3c5fe6ef 100644 --- a/src/RgbdCameraSensor.cc +++ b/src/RgbdCameraSensor.cc @@ -425,12 +425,6 @@ void RgbdCameraSensorPrivate::OnNewRgbPointCloud(const float *_scan, memcpy(this->pointCloudBuffer, _scan, pointCloudBufferSize); } -////////////////////////////////////////////////// -bool RgbdCameraSensor::Update(const ignition::common::Time &_now) -{ - return this->Update(math::secNsecToDuration(_now.sec, _now.nsec)); -} - ////////////////////////////////////////////////// bool RgbdCameraSensor::Update(const std::chrono::steady_clock::duration &_now) { diff --git a/src/Sensor.cc b/src/Sensor.cc index 21890f86..32b6e928 100644 --- a/src/Sensor.cc +++ b/src/Sensor.cc @@ -341,33 +341,12 @@ bool Sensor::Update(const std::chrono::steady_clock::duration &_now, return result; } -////////////////////////////////////////////////// -bool Sensor::Update(const ignition::common::Time &_now, const bool _force) -{ - return this->Update(math::secNsecToDuration(_now.sec, _now.nsec), _force); -} - ////////////////////////////////////////////////// std::chrono::steady_clock::duration Sensor::NextDataUpdateTime() const { return this->dataPtr->nextUpdateTime; } -////////////////////////////////////////////////// -ignition::common::Time Sensor::NextUpdateTime() const -{ -#ifndef _WIN32 -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#endif - std::pair secNsec = - math::durationToSecNsec(this->dataPtr->nextUpdateTime); - return common::Time(secNsec.first, secNsec.second); -#ifndef _WIN32 -# pragma GCC diagnostic pop -#endif -} - ///////////////////////////////////////////////// void Sensor::AddSequence(ignition::msgs::Header *_msg, const std::string &_seqKey) diff --git a/src/Sensor_TEST.cc b/src/Sensor_TEST.cc index abe911b0..835a2d53 100644 --- a/src/Sensor_TEST.cc +++ b/src/Sensor_TEST.cc @@ -32,11 +32,6 @@ class TestSensor : public Sensor return true; } - public: bool Update(const common::Time &) override - { - return false; - } - public: unsigned int updateCount{0}; }; diff --git a/src/ThermalCameraSensor.cc b/src/ThermalCameraSensor.cc index 7dac341f..bf1870bf 100644 --- a/src/ThermalCameraSensor.cc +++ b/src/ThermalCameraSensor.cc @@ -402,12 +402,6 @@ void ThermalCameraSensor::SetScene(ignition::rendering::ScenePtr _scene) } } -////////////////////////////////////////////////// -bool ThermalCameraSensor::Update(const ignition::common::Time &_now) -{ - return this->Update(math::secNsecToDuration(_now.sec, _now.nsec)); -} - ////////////////////////////////////////////////// bool ThermalCameraSensor::Update( const std::chrono::steady_clock::duration &_now) diff --git a/test/integration/gpu_lidar_sensor_plugin.cc b/test/integration/gpu_lidar_sensor_plugin.cc index 4d538c6c..ca4c022c 100644 --- a/test/integration/gpu_lidar_sensor_plugin.cc +++ b/test/integration/gpu_lidar_sensor_plugin.cc @@ -20,7 +20,6 @@ #include #include #include -#include #include #include #include diff --git a/test/integration/logical_camera_plugin.cc b/test/integration/logical_camera_plugin.cc index dd3bcc0a..61191220 100644 --- a/test/integration/logical_camera_plugin.cc +++ b/test/integration/logical_camera_plugin.cc @@ -20,7 +20,6 @@ #include #include -#include #include #include