From a51649362b4ec5d6f0a8568ea1c9877e4fda6f16 Mon Sep 17 00:00:00 2001 From: "Addisu Z. Taddese" Date: Tue, 25 Jul 2023 17:08:05 -0500 Subject: [PATCH] Remove deprecations (#365) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Remove functions that were deprecated in gz-sensors7. Also remove ignition headers. --------- Signed-off-by: Addisu Z. Taddese Signed-off-by: Alejandro Hernández Cordero Co-authored-by: Alejandro Hernández Cordero --- include/CMakeLists.txt | 1 - include/gz/sensors/Manager.hh | 48 -------------- include/gz/sensors/SensorFactory.hh | 64 ------------------- include/ignition/sensors.hh | 19 ------ include/ignition/sensors/AirPressureSensor.hh | 19 ------ include/ignition/sensors/AltimeterSensor.hh | 19 ------ .../sensors/BoundingBoxCameraSensor.hh | 19 ------ .../ignition/sensors/BrownDistortionModel.hh | 19 ------ include/ignition/sensors/CameraSensor.hh | 19 ------ include/ignition/sensors/DepthCameraSensor.hh | 19 ------ include/ignition/sensors/Distortion.hh | 19 ------ include/ignition/sensors/Export.hh | 19 ------ include/ignition/sensors/ForceTorqueSensor.hh | 19 ------ .../ignition/sensors/GaussianNoiseModel.hh | 19 ------ include/ignition/sensors/GpuLidarSensor.hh | 19 ------ .../sensors/ImageBrownDistortionModel.hh | 19 ------ include/ignition/sensors/ImageDistortion.hh | 19 ------ .../sensors/ImageGaussianNoiseModel.hh | 19 ------ include/ignition/sensors/ImageNoise.hh | 19 ------ include/ignition/sensors/ImuSensor.hh | 19 ------ include/ignition/sensors/Lidar.hh | 19 ------ .../ignition/sensors/LogicalCameraSensor.hh | 19 ------ .../ignition/sensors/MagnetometerSensor.hh | 19 ------ include/ignition/sensors/Manager.hh | 19 ------ include/ignition/sensors/NavSatSensor.hh | 19 ------ include/ignition/sensors/Noise.hh | 19 ------ include/ignition/sensors/RenderingEvents.hh | 19 ------ include/ignition/sensors/RenderingSensor.hh | 19 ------ include/ignition/sensors/RgbdCameraSensor.hh | 19 ------ .../sensors/SegmentationCameraSensor.hh | 19 ------ include/ignition/sensors/Sensor.hh | 19 ------ include/ignition/sensors/SensorFactory.hh | 19 ------ include/ignition/sensors/SensorTypes.hh | 19 ------ .../ignition/sensors/ThermalCameraSensor.hh | 19 ------ include/ignition/sensors/Util.hh | 19 ------ .../ignition/sensors/WideAngleCameraSensor.hh | 19 ------ .../ignition/sensors/air_pressure/Export.hh | 19 ------ include/ignition/sensors/altimeter/Export.hh | 18 ------ .../sensors/boundingbox_camera/Export.hh | 19 ------ include/ignition/sensors/camera/Export.hh | 19 ------ include/ignition/sensors/config.hh | 46 ------------- .../ignition/sensors/depth_camera/Export.hh | 19 ------ .../ignition/sensors/force_torque/Export.hh | 19 ------ include/ignition/sensors/gpu_lidar/Export.hh | 19 ------ include/ignition/sensors/imu/Export.hh | 19 ------ include/ignition/sensors/lidar/Export.hh | 19 ------ .../ignition/sensors/logical_camera/Export.hh | 19 ------ .../ignition/sensors/magnetometer/Export.hh | 19 ------ include/ignition/sensors/navsat/Export.hh | 19 ------ include/ignition/sensors/rendering/Export.hh | 19 ------ .../ignition/sensors/rgbd_camera/Export.hh | 19 ------ .../sensors/segmentation_camera/Export.hh | 19 ------ .../ignition/sensors/thermal_camera/Export.hh | 19 ------ .../sensors/wide_angle_camera/Export.hh | 19 ------ src/Manager.cc | 41 +++--------- src/Sensor.cc | 12 +--- src/SensorFactory.cc | 25 -------- src/Util.cc | 15 +---- 58 files changed, 11 insertions(+), 1190 deletions(-) delete mode 100644 include/ignition/sensors.hh delete mode 100644 include/ignition/sensors/AirPressureSensor.hh delete mode 100644 include/ignition/sensors/AltimeterSensor.hh delete mode 100644 include/ignition/sensors/BoundingBoxCameraSensor.hh delete mode 100644 include/ignition/sensors/BrownDistortionModel.hh delete mode 100644 include/ignition/sensors/CameraSensor.hh delete mode 100644 include/ignition/sensors/DepthCameraSensor.hh delete mode 100644 include/ignition/sensors/Distortion.hh delete mode 100644 include/ignition/sensors/Export.hh delete mode 100644 include/ignition/sensors/ForceTorqueSensor.hh delete mode 100644 include/ignition/sensors/GaussianNoiseModel.hh delete mode 100644 include/ignition/sensors/GpuLidarSensor.hh delete mode 100644 include/ignition/sensors/ImageBrownDistortionModel.hh delete mode 100644 include/ignition/sensors/ImageDistortion.hh delete mode 100644 include/ignition/sensors/ImageGaussianNoiseModel.hh delete mode 100644 include/ignition/sensors/ImageNoise.hh delete mode 100644 include/ignition/sensors/ImuSensor.hh delete mode 100644 include/ignition/sensors/Lidar.hh delete mode 100644 include/ignition/sensors/LogicalCameraSensor.hh delete mode 100644 include/ignition/sensors/MagnetometerSensor.hh delete mode 100644 include/ignition/sensors/Manager.hh delete mode 100644 include/ignition/sensors/NavSatSensor.hh delete mode 100644 include/ignition/sensors/Noise.hh delete mode 100644 include/ignition/sensors/RenderingEvents.hh delete mode 100644 include/ignition/sensors/RenderingSensor.hh delete mode 100644 include/ignition/sensors/RgbdCameraSensor.hh delete mode 100644 include/ignition/sensors/SegmentationCameraSensor.hh delete mode 100644 include/ignition/sensors/Sensor.hh delete mode 100644 include/ignition/sensors/SensorFactory.hh delete mode 100644 include/ignition/sensors/SensorTypes.hh delete mode 100644 include/ignition/sensors/ThermalCameraSensor.hh delete mode 100644 include/ignition/sensors/Util.hh delete mode 100644 include/ignition/sensors/WideAngleCameraSensor.hh delete mode 100644 include/ignition/sensors/air_pressure/Export.hh delete mode 100644 include/ignition/sensors/altimeter/Export.hh delete mode 100644 include/ignition/sensors/boundingbox_camera/Export.hh delete mode 100644 include/ignition/sensors/camera/Export.hh delete mode 100644 include/ignition/sensors/config.hh delete mode 100644 include/ignition/sensors/depth_camera/Export.hh delete mode 100644 include/ignition/sensors/force_torque/Export.hh delete mode 100644 include/ignition/sensors/gpu_lidar/Export.hh delete mode 100644 include/ignition/sensors/imu/Export.hh delete mode 100644 include/ignition/sensors/lidar/Export.hh delete mode 100644 include/ignition/sensors/logical_camera/Export.hh delete mode 100644 include/ignition/sensors/magnetometer/Export.hh delete mode 100644 include/ignition/sensors/navsat/Export.hh delete mode 100644 include/ignition/sensors/rendering/Export.hh delete mode 100644 include/ignition/sensors/rgbd_camera/Export.hh delete mode 100644 include/ignition/sensors/segmentation_camera/Export.hh delete mode 100644 include/ignition/sensors/thermal_camera/Export.hh delete mode 100644 include/ignition/sensors/wide_angle_camera/Export.hh diff --git a/include/CMakeLists.txt b/include/CMakeLists.txt index 992a1312..a35a0475 100644 --- a/include/CMakeLists.txt +++ b/include/CMakeLists.txt @@ -1,2 +1 @@ add_subdirectory(gz) -install(DIRECTORY ignition DESTINATION ${GZ_INCLUDE_INSTALL_DIR_FULL}) diff --git a/include/gz/sensors/Manager.hh b/include/gz/sensors/Manager.hh index 97b9036e..bdcc8e7c 100644 --- a/include/gz/sensors/Manager.hh +++ b/include/gz/sensors/Manager.hh @@ -89,51 +89,6 @@ namespace gz return result; } - /// \brief Create a sensor from SDF without a known sensor type. - /// - /// This creates sensors by looking at the given sdf element. - /// Sensors created with this API offer an gz-transport interface. - /// If you need a direct C++ interface to the data, you must get the - /// sensor pointer and cast to the correct type. - /// - /// A `` tag may have multiple `` tags. A SensorId will - /// be returned for each plugin that is described in SDF. - /// If there are no `` tags then one of the plugins shipped with - /// this library will be loaded. For example, a `` tag with - /// `` but no `` will load a CameraSensor from - /// gz-sensors-camera. - /// \sa Sensor() - /// \param[in] _sdf pointer to the sdf element - /// \return A sensor id that refers to the created sensor. NO_SENSOR - /// is returned on erro. - /// \deprecated Sensor registration is deprecated, so it's necessary to - /// provide the specific sensor type to create it. Use the templated - /// `CreateSensor` function. - public: gz::sensors::SensorId GZ_DEPRECATED(6) CreateSensor( - sdf::ElementPtr _sdf); - - /// \brief Create a sensor from SDF without a known sensor type. - /// - /// This creates sensors by looking at the given sdf element. - /// Sensors created with this API offer an gz-transport interface. - /// If you need a direct C++ interface to the data, you must get the - /// sensor pointer and cast to the correct type. - /// - /// A `` tag may have multiple `` tags. A SensorId will - /// be returned for each plugin that is described in SDF. - /// If there are no `` tags then one of the plugins shipped with - /// this library will be loaded. For example, a `` tag with - /// `` but no `` will load a CameraSensor from - /// gz-sensors-camera. - /// \sa Sensor() - /// \param[in] _sdf SDF sensor DOM object - /// \return A sensor id that refers to the created sensor. NO_SENSOR - /// is returned on erro. - /// \deprecated Sensor registration is deprecated, so it's necessary to - /// provide the specific sensor type to create it. Use the templated - /// `CreateSensor` function. - public: gz::sensors::SensorId GZ_DEPRECATED(6) CreateSensor( - const sdf::Sensor &_sdf); /// \brief Add a sensor for this manager to manage. /// \sa Sensor() @@ -160,9 +115,6 @@ namespace gz public: void RunOnce(const std::chrono::steady_clock::duration &_time, bool _force = false); - /// \brief Adds colon delimited paths sensor plugins may be - public: void GZ_DEPRECATED(6) AddPluginPaths(const std::string &_path); - GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief private data pointer private: std::unique_ptr dataPtr; diff --git a/include/gz/sensors/SensorFactory.hh b/include/gz/sensors/SensorFactory.hh index 84473a4e..be81f08c 100644 --- a/include/gz/sensors/SensorFactory.hh +++ b/include/gz/sensors/SensorFactory.hh @@ -39,30 +39,6 @@ namespace gz // forward declaration class SensorFactoryPrivate; - /// \brief Base sensor plugin interface - /// \deprecated Sensor plugins are deprecated. Instantiate sensor objects - /// instead. - class GZ_SENSORS_VISIBLE SensorPlugin - { - /// \brief Instantiate new sensor - /// \return New sensor - public: virtual Sensor GZ_DEPRECATED(6) * New() = 0; - }; - - /// \brief Templated class for instantiating sensors of the specified type - /// \tparam Type of sensor being instantiated. - /// \deprecated Sensor plugins are deprecated. Instantiate sensor objects - /// instead. - template - class SensorTypePlugin : public SensorPlugin - { - // Documentation inherited - public: SensorType GZ_DEPRECATED(6) * New() override - { - return new SensorType(); - }; - }; - /// \brief A factory class for creating sensors /// This class instantiates sensor objects based on the sensor type and /// makes sure they're initialized correctly. @@ -162,46 +138,6 @@ namespace gz return sensor; } - /// \brief Create a sensor from SDF without a known sensor type. - /// - /// This creates sensors by looking at the given sdf element. - /// Sensors created with this API offer an gz-transport interface. - /// If you need a direct C++ interface to the data, you must get the - /// sensor pointer and cast to the correct type. - /// - /// \sa Sensor() - /// \param[in] _sdf pointer to the sdf element - /// \return Null, as the function is deprecated. - /// \deprecated Sensor registration is deprecated, so it's necessary to - /// provide the specific sensor type to create it. Use the templated - /// `CreateSensor` function. - public: std::unique_ptr GZ_DEPRECATED(6) CreateSensor( - sdf::ElementPtr _sdf); - - /// \brief Create a sensor from an SDF Sensor DOM object without a known - /// sensor type. - /// - /// This creates sensors by looking at the given SDF Sensor DOM - /// object. - /// Sensors created with this API offer a gz-transport interface. - /// If you need a direct C++ interface to the data, you must get the - /// sensor pointer and cast to the correct type. - /// - /// \sa Sensor() - /// \param[in] _sdf SDF Sensor DOM object. - /// \return A sensor id that refers to the created sensor. Null is - /// is returned on error. - /// \deprecated Sensor registration is deprecated, so it's necessary to - /// provide the specific sensor type to create it. Use the templated - /// `CreateSensor` function. - public: std::unique_ptr GZ_DEPRECATED(6) CreateSensor( - const sdf::Sensor &_sdf); - - /// \brief Add additional path to search for sensor plugins - /// \param[in] _path Search path - /// \deprecated Sensor plugins aren't supported anymore. - public: void GZ_DEPRECATED(6) AddPluginPaths(const std::string &_path); - GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief private data pointer private: std::unique_ptr dataPtr; diff --git a/include/ignition/sensors.hh b/include/ignition/sensors.hh deleted file mode 100644 index c71c526e..00000000 --- a/include/ignition/sensors.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/AirPressureSensor.hh b/include/ignition/sensors/AirPressureSensor.hh deleted file mode 100644 index f8ee87f7..00000000 --- a/include/ignition/sensors/AirPressureSensor.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/AltimeterSensor.hh b/include/ignition/sensors/AltimeterSensor.hh deleted file mode 100644 index bc14c876..00000000 --- a/include/ignition/sensors/AltimeterSensor.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/BoundingBoxCameraSensor.hh b/include/ignition/sensors/BoundingBoxCameraSensor.hh deleted file mode 100644 index 672fbd86..00000000 --- a/include/ignition/sensors/BoundingBoxCameraSensor.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/BrownDistortionModel.hh b/include/ignition/sensors/BrownDistortionModel.hh deleted file mode 100644 index ed617035..00000000 --- a/include/ignition/sensors/BrownDistortionModel.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/CameraSensor.hh b/include/ignition/sensors/CameraSensor.hh deleted file mode 100644 index bb538944..00000000 --- a/include/ignition/sensors/CameraSensor.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/DepthCameraSensor.hh b/include/ignition/sensors/DepthCameraSensor.hh deleted file mode 100644 index 59a62f41..00000000 --- a/include/ignition/sensors/DepthCameraSensor.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/Distortion.hh b/include/ignition/sensors/Distortion.hh deleted file mode 100644 index defb0c1f..00000000 --- a/include/ignition/sensors/Distortion.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/Export.hh b/include/ignition/sensors/Export.hh deleted file mode 100644 index db719f28..00000000 --- a/include/ignition/sensors/Export.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/ForceTorqueSensor.hh b/include/ignition/sensors/ForceTorqueSensor.hh deleted file mode 100644 index fbf6f74e..00000000 --- a/include/ignition/sensors/ForceTorqueSensor.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/GaussianNoiseModel.hh b/include/ignition/sensors/GaussianNoiseModel.hh deleted file mode 100644 index 0c2b8f15..00000000 --- a/include/ignition/sensors/GaussianNoiseModel.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/GpuLidarSensor.hh b/include/ignition/sensors/GpuLidarSensor.hh deleted file mode 100644 index 46a87866..00000000 --- a/include/ignition/sensors/GpuLidarSensor.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/ImageBrownDistortionModel.hh b/include/ignition/sensors/ImageBrownDistortionModel.hh deleted file mode 100644 index 10ce3f0e..00000000 --- a/include/ignition/sensors/ImageBrownDistortionModel.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/ImageDistortion.hh b/include/ignition/sensors/ImageDistortion.hh deleted file mode 100644 index 22a3c6c4..00000000 --- a/include/ignition/sensors/ImageDistortion.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/ImageGaussianNoiseModel.hh b/include/ignition/sensors/ImageGaussianNoiseModel.hh deleted file mode 100644 index 37574ca4..00000000 --- a/include/ignition/sensors/ImageGaussianNoiseModel.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/ImageNoise.hh b/include/ignition/sensors/ImageNoise.hh deleted file mode 100644 index dd1f3cf0..00000000 --- a/include/ignition/sensors/ImageNoise.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/ImuSensor.hh b/include/ignition/sensors/ImuSensor.hh deleted file mode 100644 index 8ab34787..00000000 --- a/include/ignition/sensors/ImuSensor.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/Lidar.hh b/include/ignition/sensors/Lidar.hh deleted file mode 100644 index f0d50f8c..00000000 --- a/include/ignition/sensors/Lidar.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/LogicalCameraSensor.hh b/include/ignition/sensors/LogicalCameraSensor.hh deleted file mode 100644 index fcc3a067..00000000 --- a/include/ignition/sensors/LogicalCameraSensor.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/MagnetometerSensor.hh b/include/ignition/sensors/MagnetometerSensor.hh deleted file mode 100644 index 85c84180..00000000 --- a/include/ignition/sensors/MagnetometerSensor.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/Manager.hh b/include/ignition/sensors/Manager.hh deleted file mode 100644 index c38ba08d..00000000 --- a/include/ignition/sensors/Manager.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/NavSatSensor.hh b/include/ignition/sensors/NavSatSensor.hh deleted file mode 100644 index 94b21b79..00000000 --- a/include/ignition/sensors/NavSatSensor.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/Noise.hh b/include/ignition/sensors/Noise.hh deleted file mode 100644 index 8c445c6a..00000000 --- a/include/ignition/sensors/Noise.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/RenderingEvents.hh b/include/ignition/sensors/RenderingEvents.hh deleted file mode 100644 index ec04546f..00000000 --- a/include/ignition/sensors/RenderingEvents.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/RenderingSensor.hh b/include/ignition/sensors/RenderingSensor.hh deleted file mode 100644 index bf04bd29..00000000 --- a/include/ignition/sensors/RenderingSensor.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/RgbdCameraSensor.hh b/include/ignition/sensors/RgbdCameraSensor.hh deleted file mode 100644 index df4ad7be..00000000 --- a/include/ignition/sensors/RgbdCameraSensor.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/SegmentationCameraSensor.hh b/include/ignition/sensors/SegmentationCameraSensor.hh deleted file mode 100644 index 5eddea5f..00000000 --- a/include/ignition/sensors/SegmentationCameraSensor.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/Sensor.hh b/include/ignition/sensors/Sensor.hh deleted file mode 100644 index 888809eb..00000000 --- a/include/ignition/sensors/Sensor.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/SensorFactory.hh b/include/ignition/sensors/SensorFactory.hh deleted file mode 100644 index 4f048a96..00000000 --- a/include/ignition/sensors/SensorFactory.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/SensorTypes.hh b/include/ignition/sensors/SensorTypes.hh deleted file mode 100644 index 43953a29..00000000 --- a/include/ignition/sensors/SensorTypes.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/ThermalCameraSensor.hh b/include/ignition/sensors/ThermalCameraSensor.hh deleted file mode 100644 index c3132e57..00000000 --- a/include/ignition/sensors/ThermalCameraSensor.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/Util.hh b/include/ignition/sensors/Util.hh deleted file mode 100644 index d0685347..00000000 --- a/include/ignition/sensors/Util.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/WideAngleCameraSensor.hh b/include/ignition/sensors/WideAngleCameraSensor.hh deleted file mode 100644 index a1f06dd5..00000000 --- a/include/ignition/sensors/WideAngleCameraSensor.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2021 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/air_pressure/Export.hh b/include/ignition/sensors/air_pressure/Export.hh deleted file mode 100644 index e42e8a24..00000000 --- a/include/ignition/sensors/air_pressure/Export.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/altimeter/Export.hh b/include/ignition/sensors/altimeter/Export.hh deleted file mode 100644 index 78a1a5ab..00000000 --- a/include/ignition/sensors/altimeter/Export.hh +++ /dev/null @@ -1,18 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ -#include -#include diff --git a/include/ignition/sensors/boundingbox_camera/Export.hh b/include/ignition/sensors/boundingbox_camera/Export.hh deleted file mode 100644 index be727903..00000000 --- a/include/ignition/sensors/boundingbox_camera/Export.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/camera/Export.hh b/include/ignition/sensors/camera/Export.hh deleted file mode 100644 index 9daecc36..00000000 --- a/include/ignition/sensors/camera/Export.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/config.hh b/include/ignition/sensors/config.hh deleted file mode 100644 index 813c8564..00000000 --- a/include/ignition/sensors/config.hh +++ /dev/null @@ -1,46 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#ifndef IGNITION_SENSORS__CONFIG_HH_ -#define IGNITION_SENSORS__CONFIG_HH_ - -#include - -#define IGNITION_SENSORS_MAJOR_VERSION GZ_SENSORS_MAJOR_VERSION -#define IGNITION_SENSORS_MINOR_VERSION GZ_SENSORS_MINOR_VERSION -#define IGNITION_SENSORS_PATCH_VERSION GZ_SENSORS_PATCH_VERSION - -#define IGNITION_SENSORS_VERSION GZ_SENSORS_VERSION -#define IGNITION_SENSORS_VERSION_FULL GZ_SENSORS_VERSION_FULL - -#define IGNITION_SENSORS_VERSION_NAMESPACE GZ_SENSORS_VERSION_NAMESPACE - -#define IGNITION_SENSORS_VERSION_HEADER GZ_SENSORS_VERSION_HEADER - -namespace gz -{ -} - -namespace ignition -{ - #ifndef SUPPRESS_IGNITION_HEADER_DEPRECATION - #pragma message("ignition namespace is deprecated! Use gz instead!") - #endif - using namespace gz; -} - -#endif diff --git a/include/ignition/sensors/depth_camera/Export.hh b/include/ignition/sensors/depth_camera/Export.hh deleted file mode 100644 index 65f7b883..00000000 --- a/include/ignition/sensors/depth_camera/Export.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/force_torque/Export.hh b/include/ignition/sensors/force_torque/Export.hh deleted file mode 100644 index e6e0aa98..00000000 --- a/include/ignition/sensors/force_torque/Export.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/gpu_lidar/Export.hh b/include/ignition/sensors/gpu_lidar/Export.hh deleted file mode 100644 index 68d622d5..00000000 --- a/include/ignition/sensors/gpu_lidar/Export.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/imu/Export.hh b/include/ignition/sensors/imu/Export.hh deleted file mode 100644 index 8b72f096..00000000 --- a/include/ignition/sensors/imu/Export.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/lidar/Export.hh b/include/ignition/sensors/lidar/Export.hh deleted file mode 100644 index ab3b0160..00000000 --- a/include/ignition/sensors/lidar/Export.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/logical_camera/Export.hh b/include/ignition/sensors/logical_camera/Export.hh deleted file mode 100644 index 16b13bf0..00000000 --- a/include/ignition/sensors/logical_camera/Export.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/magnetometer/Export.hh b/include/ignition/sensors/magnetometer/Export.hh deleted file mode 100644 index 83d0397b..00000000 --- a/include/ignition/sensors/magnetometer/Export.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/navsat/Export.hh b/include/ignition/sensors/navsat/Export.hh deleted file mode 100644 index 33b96ddb..00000000 --- a/include/ignition/sensors/navsat/Export.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/rendering/Export.hh b/include/ignition/sensors/rendering/Export.hh deleted file mode 100644 index c59400d9..00000000 --- a/include/ignition/sensors/rendering/Export.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/rgbd_camera/Export.hh b/include/ignition/sensors/rgbd_camera/Export.hh deleted file mode 100644 index 76ab66e3..00000000 --- a/include/ignition/sensors/rgbd_camera/Export.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/segmentation_camera/Export.hh b/include/ignition/sensors/segmentation_camera/Export.hh deleted file mode 100644 index 4e3ca411..00000000 --- a/include/ignition/sensors/segmentation_camera/Export.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/thermal_camera/Export.hh b/include/ignition/sensors/thermal_camera/Export.hh deleted file mode 100644 index dd37a865..00000000 --- a/include/ignition/sensors/thermal_camera/Export.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/sensors/wide_angle_camera/Export.hh b/include/ignition/sensors/wide_angle_camera/Export.hh deleted file mode 100644 index 14778a08..00000000 --- a/include/ignition/sensors/wide_angle_camera/Export.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2019 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/src/Manager.cc b/src/Manager.cc index a68c5149..7a68f17e 100644 --- a/src/Manager.cc +++ b/src/Manager.cc @@ -59,30 +59,12 @@ gz::sensors::Sensor *Manager::Sensor( return iter != this->dataPtr->sensors.end() ? iter->second.get() : nullptr; } -////////////////////////////////////////////////// -void Manager::AddPluginPaths(const std::string &) -{ - gzwarn << "Trying to add plugin paths, but Gazebo Sensors doesn't support" - << " plugins anymore." << std::endl; -} - ////////////////////////////////////////////////// bool Manager::Remove(const gz::sensors::SensorId _id) { return this->dataPtr->sensors.erase(_id) > 0; } -////////////////////////////////////////////////// -void Manager::RunOnce( - const std::chrono::steady_clock::duration &_time, bool _force) -{ - GZ_PROFILE("SensorManager::RunOnce"); - for (auto &s : this->dataPtr->sensors) - { - s.second->Update(_time, _force); - } -} - ///////////////////////////////////////////////// SensorId Manager::AddSensor( std::unique_ptr _sensor) @@ -94,20 +76,13 @@ SensorId Manager::AddSensor( return id; } -///////////////////////////////////////////////// -gz::sensors::SensorId Manager::CreateSensor(const sdf::Sensor &) -{ - gzwarn << "Trying to create sensor without providing sensor type. Gazebo" - << " Sensors doesn't support sensor registration anymore. Use the" - << " templated `CreateSensor` function instead." << std::endl; - return NO_SENSOR; -} - -///////////////////////////////////////////////// -gz::sensors::SensorId Manager::CreateSensor(sdf::ElementPtr) +////////////////////////////////////////////////// +void Manager::RunOnce( + const std::chrono::steady_clock::duration &_time, bool _force) { - gzwarn << "Trying to create sensor without providing sensor type. Gazebo" - << " Sensors doesn't support sensor registration anymore. Use the" - << " templated `CreateSensor` function instead." << std::endl; - return NO_SENSOR; + GZ_PROFILE("SensorManager::RunOnce"); + for (auto &s : this->dataPtr->sensors) + { + s.second->Update(_time, _force); + } } diff --git a/src/Sensor.cc b/src/Sensor.cc index ef6c10bd..01385ac7 100644 --- a/src/Sensor.cc +++ b/src/Sensor.cc @@ -161,17 +161,7 @@ bool SensorPrivate::PopulateFromSDF(const sdf::Sensor &_sdf) } else { - // TODO(ahcorde): Remove this deprecation in gz-sensors8 - if (element->HasElement("ignition_frame_id")) - { - gzwarn << "The `ignition_frame_id` tag is deprecated. " - << "Please use `gz_frame_id` instead." << std::endl; - this->frame_id = element->Get("ignition_frame_id"); - } - else - { - this->frame_id = this->name; - } + this->frame_id = this->name; } } diff --git a/src/SensorFactory.cc b/src/SensorFactory.cc index 4012baf6..97bc53fd 100644 --- a/src/SensorFactory.cc +++ b/src/SensorFactory.cc @@ -27,13 +27,6 @@ class gz::sensors::SensorFactoryPrivate using namespace gz; using namespace sensors; -////////////////////////////////////////////////// -void SensorFactory::AddPluginPaths(const std::string &) -{ - gzwarn << "Trying to add plugin paths, but Gazebo Sensors doesn't support" - << " plugins anymore." << std::endl; -} - ////////////////////////////////////////////////// SensorFactory::SensorFactory() : dataPtr(new SensorFactoryPrivate) { @@ -43,21 +36,3 @@ SensorFactory::SensorFactory() : dataPtr(new SensorFactoryPrivate) SensorFactory::~SensorFactory() { } - -///////////////////////////////////////////////// -std::unique_ptr SensorFactory::CreateSensor(const sdf::Sensor &) -{ - gzwarn << "Trying to create sensor without providing sensor type. Gazebo" - << " Sensors doesn't support sensor registration anymore. Use the" - << " templated `CreateSensor` function instead." << std::endl; - return nullptr; -} - -///////////////////////////////////////////////// -std::unique_ptr SensorFactory::CreateSensor(sdf::ElementPtr) -{ - gzwarn << "Trying to create sensor without providing sensor type. Gazebo" - << " Sensors doesn't support sensor registration anymore. Use the" - << " templated `CreateSensor` function instead." << std::endl; - return nullptr; -} diff --git a/src/Util.cc b/src/Util.cc index f7fc0a3b..7e769eac 100644 --- a/src/Util.cc +++ b/src/Util.cc @@ -49,19 +49,8 @@ std::string gz::sensors::customType(sdf::ElementPtr _sdf) if (!_sdf->HasAttribute("gz:type")) { - // TODO(CH3): Deprecated. Remove on tock. - // Try deprecated ignition:type attribute if gz:type attribute is missing - if (_sdf->HasAttribute("ignition:type")) - { - gzwarn << "The `ignition:type` attribute is deprecated. Please use " - << "`gz:type` instead." << std::endl; - return _sdf->Get("ignition:type"); - } - else - { - gzerr << "Custom sensor missing `gz:type` attribute." << std::endl; - return std::string(); - } + gzerr << "Custom sensor missing `gz:type` attribute." << std::endl; + return std::string(); } return _sdf->Get("gz:type");