From a51fc7dd7fa6167e09409b7f5dbfadc91c4ed6ad Mon Sep 17 00:00:00 2001 From: methylDragon Date: Fri, 6 May 2022 15:01:19 -0700 Subject: [PATCH] Migrate sources in src, test, examples, and include (#221) Signed-off-by: methylDragon --- examples/custom_sensor/Odometer.cc | 8 +++---- examples/custom_sensor/Odometer.hh | 6 ++--- examples/imu_noise/main.cc | 6 ++--- examples/loop_sensor/main.cc | 8 +++---- examples/save_image/main.cc | 18 +++++++------- include/gz/sensors/AirPressureSensor.hh | 12 +++++----- include/gz/sensors/AltimeterSensor.hh | 12 +++++----- include/gz/sensors/BrownDistortionModel.hh | 14 +++++------ include/gz/sensors/CameraSensor.hh | 18 +++++++------- include/gz/sensors/DepthCameraSensor.hh | 20 ++++++++-------- include/gz/sensors/Distortion.hh | 16 ++++++------- include/gz/sensors/ForceTorqueSensor.hh | 14 +++++------ include/gz/sensors/GaussianNoiseModel.hh | 12 +++++----- include/gz/sensors/GpuLidarSensor.hh | 14 +++++------ .../gz/sensors/ImageBrownDistortionModel.hh | 14 +++++------ include/gz/sensors/ImageDistortion.hh | 12 +++++----- include/gz/sensors/ImageGaussianNoiseModel.hh | 14 +++++------ include/gz/sensors/ImageNoise.hh | 12 +++++----- include/gz/sensors/ImuSensor.hh | 14 +++++------ include/gz/sensors/Lidar.hh | 12 +++++----- include/gz/sensors/LogicalCameraSensor.hh | 18 +++++++------- include/gz/sensors/MagnetometerSensor.hh | 14 +++++------ include/gz/sensors/Manager.hh | 16 ++++++------- include/gz/sensors/NavSatSensor.hh | 12 +++++----- include/gz/sensors/Noise.hh | 14 +++++------ include/gz/sensors/RenderingEvents.hh | 14 +++++------ include/gz/sensors/RenderingSensor.hh | 12 +++++----- include/gz/sensors/RgbdCameraSensor.hh | 14 +++++------ .../gz/sensors/SegmentationCameraSensor.hh | 24 +++++++++---------- include/gz/sensors/Sensor.hh | 14 +++++------ include/gz/sensors/SensorFactory.hh | 14 +++++------ include/gz/sensors/SensorTypes.hh | 14 +++++------ include/gz/sensors/ThermalCameraSensor.hh | 20 ++++++++-------- include/gz/sensors/Util.hh | 8 +++---- include/gz/sensors/WideAngleCameraSensor.hh | 20 ++++++++-------- include/gz/sensors/sensors.hh.in | 2 +- 36 files changed, 243 insertions(+), 243 deletions(-) diff --git a/examples/custom_sensor/Odometer.cc b/examples/custom_sensor/Odometer.cc index 326bae4f..60a3c053 100644 --- a/examples/custom_sensor/Odometer.cc +++ b/examples/custom_sensor/Odometer.cc @@ -17,11 +17,11 @@ #include -#include +#include -#include -#include -#include +#include +#include +#include #include "Odometer.hh" diff --git a/examples/custom_sensor/Odometer.hh b/examples/custom_sensor/Odometer.hh index 17494fbe..7efc3f30 100644 --- a/examples/custom_sensor/Odometer.hh +++ b/examples/custom_sensor/Odometer.hh @@ -17,9 +17,9 @@ #ifndef ODOMETER_HH_ #define ODOMETER_HH_ -#include -#include -#include +#include +#include +#include namespace custom { diff --git a/examples/imu_noise/main.cc b/examples/imu_noise/main.cc index 04b02333..3050c455 100644 --- a/examples/imu_noise/main.cc +++ b/examples/imu_noise/main.cc @@ -20,9 +20,9 @@ #include -#include -#include -#include +#include +#include +#include static constexpr double kSampleFrequency = 100.0; // 16-bit ADC diff --git a/examples/loop_sensor/main.cc b/examples/loop_sensor/main.cc index be80b415..2b408d4f 100644 --- a/examples/loop_sensor/main.cc +++ b/examples/loop_sensor/main.cc @@ -19,12 +19,12 @@ #include -#include -#include -#include +#include +#include +#include // Include all supported sensors -#include +#include #include "../custom_sensor/Odometer.hh" using namespace std::literals::chrono_literals; diff --git a/examples/save_image/main.cc b/examples/save_image/main.cc index cfbcfac7..dd54686c 100644 --- a/examples/save_image/main.cc +++ b/examples/save_image/main.cc @@ -21,9 +21,9 @@ #include #include -#include -#include -#include +#include +#include +#include // TODO(louise) Remove these pragmas once ign-rendering is disabling the // warnings @@ -31,16 +31,16 @@ #pragma warning(push) #pragma warning(disable: 4251) #endif -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #ifdef _WIN32 #pragma warning(pop) #endif -#include +#include void OnImageFrame(const ignition::msgs::Image &_image) { diff --git a/include/gz/sensors/AirPressureSensor.hh b/include/gz/sensors/AirPressureSensor.hh index 7f4afab2..b3e7752d 100644 --- a/include/gz/sensors/AirPressureSensor.hh +++ b/include/gz/sensors/AirPressureSensor.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_SENSORS_AIRPRESSURESENSOR_HH_ -#define IGNITION_SENSORS_AIRPRESSURESENSOR_HH_ +#ifndef GZ_SENSORS_AIRPRESSURESENSOR_HH_ +#define GZ_SENSORS_AIRPRESSURESENSOR_HH_ #include #include -#include +#include -#include -#include +#include +#include -#include "ignition/sensors/Sensor.hh" +#include "gz/sensors/Sensor.hh" namespace ignition { diff --git a/include/gz/sensors/AltimeterSensor.hh b/include/gz/sensors/AltimeterSensor.hh index 31910613..503484ae 100644 --- a/include/gz/sensors/AltimeterSensor.hh +++ b/include/gz/sensors/AltimeterSensor.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_SENSORS_ALTIMETERSENSOR_HH_ -#define IGNITION_SENSORS_ALTIMETERSENSOR_HH_ +#ifndef GZ_SENSORS_ALTIMETERSENSOR_HH_ +#define GZ_SENSORS_ALTIMETERSENSOR_HH_ #include #include -#include +#include -#include -#include +#include +#include -#include "ignition/sensors/Sensor.hh" +#include "gz/sensors/Sensor.hh" namespace ignition { diff --git a/include/gz/sensors/BrownDistortionModel.hh b/include/gz/sensors/BrownDistortionModel.hh index 388c6d66..9a1a74d3 100644 --- a/include/gz/sensors/BrownDistortionModel.hh +++ b/include/gz/sensors/BrownDistortionModel.hh @@ -15,15 +15,15 @@ * */ -#ifndef IGNITION_SENSORS_BROWNDISTORTIONMODEL_HH_ -#define IGNITION_SENSORS_BROWNDISTORTIONMODEL_HH_ +#ifndef GZ_SENSORS_BROWNDISTORTIONMODEL_HH_ +#define GZ_SENSORS_BROWNDISTORTIONMODEL_HH_ #include -#include "ignition/sensors/Distortion.hh" -#include "ignition/sensors/Export.hh" -#include "ignition/sensors/config.hh" -#include "ignition/utils/ImplPtr.hh" +#include "gz/sensors/Distortion.hh" +#include "gz/sensors/Export.hh" +#include "gz/sensors/config.hh" +#include "gz/utils/ImplPtr.hh" namespace ignition { @@ -36,7 +36,7 @@ namespace ignition class BrownDistortionModelPrivate; /** \class BrownDistortionModel BrownDistortionModel.hh \ - ignition/sensors/BrownDistortionModel.hh + gz/sensors/BrownDistortionModel.hh **/ /// \brief Brown Distortion Model class class IGNITION_SENSORS_VISIBLE BrownDistortionModel : public Distortion diff --git a/include/gz/sensors/CameraSensor.hh b/include/gz/sensors/CameraSensor.hh index 7d78ac45..e1205686 100644 --- a/include/gz/sensors/CameraSensor.hh +++ b/include/gz/sensors/CameraSensor.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_SENSORS_CAMERASENSOR_HH_ -#define IGNITION_SENSORS_CAMERASENSOR_HH_ +#ifndef GZ_SENSORS_CAMERASENSOR_HH_ +#define GZ_SENSORS_CAMERASENSOR_HH_ #include #include @@ -23,14 +23,14 @@ #include -#include +#include #ifdef _WIN32 #pragma warning(push) #pragma warning(disable: 4005) #pragma warning(disable: 4251) #endif -#include +#include #ifdef _WIN32 #pragma warning(pop) #endif @@ -41,15 +41,15 @@ #pragma warning(push) #pragma warning(disable: 4251) #endif -#include +#include #ifdef _WIN32 #pragma warning(pop) #endif -#include "ignition/sensors/camera/Export.hh" -#include "ignition/sensors/config.hh" -#include "ignition/sensors/Export.hh" -#include "ignition/sensors/RenderingSensor.hh" +#include "gz/sensors/camera/Export.hh" +#include "gz/sensors/config.hh" +#include "gz/sensors/Export.hh" +#include "gz/sensors/RenderingSensor.hh" namespace ignition { diff --git a/include/gz/sensors/DepthCameraSensor.hh b/include/gz/sensors/DepthCameraSensor.hh index cac4a52d..800129bd 100644 --- a/include/gz/sensors/DepthCameraSensor.hh +++ b/include/gz/sensors/DepthCameraSensor.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_SENSORS_DEPTHCAMERASENSOR_HH_ -#define IGNITION_SENSORS_DEPTHCAMERASENSOR_HH_ +#ifndef GZ_SENSORS_DEPTHCAMERASENSOR_HH_ +#define GZ_SENSORS_DEPTHCAMERASENSOR_HH_ #include #include @@ -23,15 +23,15 @@ #include -#include -#include +#include +#include #ifdef _WIN32 #pragma warning(push) #pragma warning(disable: 4005) #pragma warning(disable: 4251) #endif -#include +#include #ifdef _WIN32 #pragma warning(pop) #endif @@ -42,15 +42,15 @@ #pragma warning(push) #pragma warning(disable: 4251) #endif -#include +#include #ifdef _WIN32 #pragma warning(pop) #endif -#include "ignition/sensors/depth_camera/Export.hh" -#include "ignition/sensors/CameraSensor.hh" -#include "ignition/sensors/Export.hh" -#include "ignition/sensors/Sensor.hh" +#include "gz/sensors/depth_camera/Export.hh" +#include "gz/sensors/CameraSensor.hh" +#include "gz/sensors/Export.hh" +#include "gz/sensors/Sensor.hh" namespace ignition { diff --git a/include/gz/sensors/Distortion.hh b/include/gz/sensors/Distortion.hh index 852c4bc9..b4e24329 100644 --- a/include/gz/sensors/Distortion.hh +++ b/include/gz/sensors/Distortion.hh @@ -15,17 +15,17 @@ * */ -#ifndef IGNITION_SENSORS_DISTORTION_HH_ -#define IGNITION_SENSORS_DISTORTION_HH_ +#ifndef GZ_SENSORS_DISTORTION_HH_ +#define GZ_SENSORS_DISTORTION_HH_ #include #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include @@ -38,7 +38,7 @@ namespace ignition // Forward declarations class DistortionPrivate; - /// \class DistortionFactory Distortion.hh ignition/sensors/Distortion.hh + /// \class DistortionFactory Distortion.hh gz/sensors/Distortion.hh /// \brief Use this distortion manager for creating and loading distortion /// models. class IGNITION_SENSORS_VISIBLE DistortionFactory @@ -73,7 +73,7 @@ namespace ignition BROWN = 2 }; - /// \class Distortion Distortion.hh ignition/sensors/Distortion.hh + /// \class Distortion Distortion.hh gz/sensors/Distortion.hh /// \brief Distortion models for sensor output signals. class IGNITION_SENSORS_VISIBLE Distortion { diff --git a/include/gz/sensors/ForceTorqueSensor.hh b/include/gz/sensors/ForceTorqueSensor.hh index f9b7121a..243d7126 100644 --- a/include/gz/sensors/ForceTorqueSensor.hh +++ b/include/gz/sensors/ForceTorqueSensor.hh @@ -15,21 +15,21 @@ * */ -#ifndef IGNITION_SENSORS_FORCETORQUESENSOR_HH_ -#define IGNITION_SENSORS_FORCETORQUESENSOR_HH_ +#ifndef GZ_SENSORS_FORCETORQUESENSOR_HH_ +#define GZ_SENSORS_FORCETORQUESENSOR_HH_ #include #include -#include +#include -#include +#include -#include -#include +#include +#include -#include "ignition/sensors/Sensor.hh" +#include "gz/sensors/Sensor.hh" namespace ignition { diff --git a/include/gz/sensors/GaussianNoiseModel.hh b/include/gz/sensors/GaussianNoiseModel.hh index 70eaec6a..5ab18168 100644 --- a/include/gz/sensors/GaussianNoiseModel.hh +++ b/include/gz/sensors/GaussianNoiseModel.hh @@ -15,14 +15,14 @@ * */ -#ifndef IGNITION_SENSORS_GAUSSIANNOISEMODEL_HH_ -#define IGNITION_SENSORS_GAUSSIANNOISEMODEL_HH_ +#ifndef GZ_SENSORS_GAUSSIANNOISEMODEL_HH_ +#define GZ_SENSORS_GAUSSIANNOISEMODEL_HH_ #include -#include "ignition/sensors/config.hh" -#include "ignition/sensors/Export.hh" -#include "ignition/sensors/Noise.hh" +#include "gz/sensors/config.hh" +#include "gz/sensors/Export.hh" +#include "gz/sensors/Noise.hh" namespace ignition { @@ -35,7 +35,7 @@ namespace ignition class GaussianNoiseModelPrivate; /** \class GaussianNoiseModel GaussianNoiseModel.hh \ - ignition/sensors/GaussianNoiseModel.hh + gz/sensors/GaussianNoiseModel.hh **/ /// \brief Gaussian noise class class IGNITION_SENSORS_VISIBLE GaussianNoiseModel : public Noise diff --git a/include/gz/sensors/GpuLidarSensor.hh b/include/gz/sensors/GpuLidarSensor.hh index 0cde9a4a..fa8bd0aa 100644 --- a/include/gz/sensors/GpuLidarSensor.hh +++ b/include/gz/sensors/GpuLidarSensor.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_SENSORS_GPULIDARSENSOR_HH_ -#define IGNITION_SENSORS_GPULIDARSENSOR_HH_ +#ifndef GZ_SENSORS_GPULIDARSENSOR_HH_ +#define GZ_SENSORS_GPULIDARSENSOR_HH_ #include #include #include -#include +#include // TODO(louise) Remove these pragmas once ign-rendering is disabling the // warnings @@ -30,14 +30,14 @@ #pragma warning(push) #pragma warning(disable: 4251) #endif -#include +#include #ifdef _WIN32 #pragma warning(pop) #endif -#include "ignition/sensors/gpu_lidar/Export.hh" -#include "ignition/sensors/RenderingEvents.hh" -#include "ignition/sensors/Lidar.hh" +#include "gz/sensors/gpu_lidar/Export.hh" +#include "gz/sensors/RenderingEvents.hh" +#include "gz/sensors/Lidar.hh" namespace ignition { diff --git a/include/gz/sensors/ImageBrownDistortionModel.hh b/include/gz/sensors/ImageBrownDistortionModel.hh index aee103c9..5ab7e4e7 100644 --- a/include/gz/sensors/ImageBrownDistortionModel.hh +++ b/include/gz/sensors/ImageBrownDistortionModel.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_SENSORS_IMAGEBROWNDISTORTIONMODEL_HH_ -#define IGNITION_SENSORS_IMAGEBROWNDISTORTIONMODEL_HH_ +#ifndef GZ_SENSORS_IMAGEBROWNDISTORTIONMODEL_HH_ +#define GZ_SENSORS_IMAGEBROWNDISTORTIONMODEL_HH_ #include @@ -26,14 +26,14 @@ #pragma warning(push) #pragma warning(disable: 4251) #endif -#include +#include #ifdef _WIN32 #pragma warning(pop) #endif -#include "ignition/sensors/config.hh" -#include "ignition/sensors/BrownDistortionModel.hh" -#include "ignition/sensors/rendering/Export.hh" +#include "gz/sensors/config.hh" +#include "gz/sensors/BrownDistortionModel.hh" +#include "gz/sensors/rendering/Export.hh" namespace ignition { @@ -45,7 +45,7 @@ namespace ignition class ImageBrownDistortionModelPrivate; /** \class ImageBrownDistortionModel ImageBrownDistortionModel.hh \ - ignition/sensors/ImageBrownDistortionModel.hh + gz/sensors/ImageBrownDistortionModel.hh **/ /// \brief Distortion Model class for image sensors class IGNITION_SENSORS_RENDERING_VISIBLE ImageBrownDistortionModel : diff --git a/include/gz/sensors/ImageDistortion.hh b/include/gz/sensors/ImageDistortion.hh index 0e39b8c7..f8e5897a 100644 --- a/include/gz/sensors/ImageDistortion.hh +++ b/include/gz/sensors/ImageDistortion.hh @@ -15,16 +15,16 @@ * */ -#ifndef IGNITION_SENSORS_IMAGEDISTORTION_HH_ -#define IGNITION_SENSORS_IMAGEDISTORTION_HH_ +#ifndef GZ_SENSORS_IMAGEDISTORTION_HH_ +#define GZ_SENSORS_IMAGEDISTORTION_HH_ #include #include -#include "ignition/sensors/config.hh" -#include "ignition/sensors/SensorTypes.hh" -#include "ignition/sensors/rendering/Export.hh" +#include "gz/sensors/config.hh" +#include "gz/sensors/SensorTypes.hh" +#include "gz/sensors/rendering/Export.hh" namespace ignition { @@ -36,7 +36,7 @@ namespace ignition class DistortionPrivate; /// \class ImageDistortionFactory ImageDistortion.hh - /// ignition/sensors/ImageDistortion.hh + /// gz/sensors/ImageDistortion.hh /// \brief Use this distortion manager for creating and loading distortion /// models. class IGNITION_SENSORS_RENDERING_VISIBLE ImageDistortionFactory diff --git a/include/gz/sensors/ImageGaussianNoiseModel.hh b/include/gz/sensors/ImageGaussianNoiseModel.hh index f20ca0bc..1f8eb84f 100644 --- a/include/gz/sensors/ImageGaussianNoiseModel.hh +++ b/include/gz/sensors/ImageGaussianNoiseModel.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_SENSORS_IMAGEGAUSSIANNOISEMODEL_HH_ -#define IGNITION_SENSORS_IMAGEGAUSSIANNOISEMODEL_HH_ +#ifndef GZ_SENSORS_IMAGEGAUSSIANNOISEMODEL_HH_ +#define GZ_SENSORS_IMAGEGAUSSIANNOISEMODEL_HH_ #include @@ -26,14 +26,14 @@ #pragma warning(push) #pragma warning(disable: 4251) #endif -#include +#include #ifdef _WIN32 #pragma warning(pop) #endif -#include "ignition/sensors/config.hh" -#include "ignition/sensors/GaussianNoiseModel.hh" -#include "ignition/sensors/rendering/Export.hh" +#include "gz/sensors/config.hh" +#include "gz/sensors/GaussianNoiseModel.hh" +#include "gz/sensors/rendering/Export.hh" namespace ignition { @@ -45,7 +45,7 @@ namespace ignition class ImageGaussianNoiseModelPrivate; /** \class ImageGaussianNoiseModel GaussianNoiseModel.hh \ - ignition/sensors/GaussianNoiseModel.hh + gz/sensors/GaussianNoiseModel.hh **/ /// \brief Gaussian noise class for image sensors class IGNITION_SENSORS_RENDERING_VISIBLE ImageGaussianNoiseModel : diff --git a/include/gz/sensors/ImageNoise.hh b/include/gz/sensors/ImageNoise.hh index 20dc2606..da21c51a 100644 --- a/include/gz/sensors/ImageNoise.hh +++ b/include/gz/sensors/ImageNoise.hh @@ -15,16 +15,16 @@ * */ -#ifndef IGNITION_SENSORS_IMAGENOISE_HH_ -#define IGNITION_SENSORS_IMAGENOISE_HH_ +#ifndef GZ_SENSORS_IMAGENOISE_HH_ +#define GZ_SENSORS_IMAGENOISE_HH_ #include #include -#include "ignition/sensors/config.hh" -#include "ignition/sensors/SensorTypes.hh" -#include "ignition/sensors/rendering/Export.hh" +#include "gz/sensors/config.hh" +#include "gz/sensors/SensorTypes.hh" +#include "gz/sensors/rendering/Export.hh" namespace ignition { @@ -35,7 +35,7 @@ namespace ignition // Forward declarations class NoisePrivate; - /// \class NoiseFactory Noise.hh ignition/sensors/Noise.hh + /// \class NoiseFactory Noise.hh gz/sensors/Noise.hh /// \brief Use this noise manager for creating and loading noise models. class IGNITION_SENSORS_RENDERING_VISIBLE ImageNoiseFactory { diff --git a/include/gz/sensors/ImuSensor.hh b/include/gz/sensors/ImuSensor.hh index a22beb4a..2a6abb74 100644 --- a/include/gz/sensors/ImuSensor.hh +++ b/include/gz/sensors/ImuSensor.hh @@ -14,20 +14,20 @@ * limitations under the License. * */ -#ifndef IGNITION_SENSORS_IMUSENSOR_HH_ -#define IGNITION_SENSORS_IMUSENSOR_HH_ +#ifndef GZ_SENSORS_IMUSENSOR_HH_ +#define GZ_SENSORS_IMUSENSOR_HH_ #include #include -#include -#include +#include +#include -#include -#include +#include +#include -#include "ignition/sensors/Sensor.hh" +#include "gz/sensors/Sensor.hh" namespace ignition { diff --git a/include/gz/sensors/Lidar.hh b/include/gz/sensors/Lidar.hh index 0feebe77..98169caf 100644 --- a/include/gz/sensors/Lidar.hh +++ b/include/gz/sensors/Lidar.hh @@ -14,18 +14,18 @@ * limitations under the License. * */ -#ifndef IGNITION_SENSORS_LIDAR_HH_ -#define IGNITION_SENSORS_LIDAR_HH_ +#ifndef GZ_SENSORS_LIDAR_HH_ +#define GZ_SENSORS_LIDAR_HH_ #include #include #include -#include -#include +#include +#include -#include "ignition/sensors/lidar/Export.hh" -#include "ignition/sensors/RenderingSensor.hh" +#include "gz/sensors/lidar/Export.hh" +#include "gz/sensors/RenderingSensor.hh" namespace ignition { diff --git a/include/gz/sensors/LogicalCameraSensor.hh b/include/gz/sensors/LogicalCameraSensor.hh index 013e75d8..0d4e3a09 100644 --- a/include/gz/sensors/LogicalCameraSensor.hh +++ b/include/gz/sensors/LogicalCameraSensor.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_SENSORS_LOGICALCAMERASENSOR_HH_ -#define IGNITION_SENSORS_LOGICALCAMERASENSOR_HH_ +#ifndef GZ_SENSORS_LOGICALCAMERASENSOR_HH_ +#define GZ_SENSORS_LOGICALCAMERASENSOR_HH_ #include #include @@ -23,24 +23,24 @@ #include -#include +#include -#include +#include #ifdef _WIN32 #pragma warning(push) #pragma warning(disable: 4005) #pragma warning(disable: 4251) #endif -#include +#include #ifdef _WIN32 #pragma warning(pop) #endif -#include "ignition/sensors/config.hh" -#include "ignition/sensors/Export.hh" -#include "ignition/sensors/logical_camera/Export.hh" -#include "ignition/sensors/Sensor.hh" +#include "gz/sensors/config.hh" +#include "gz/sensors/Export.hh" +#include "gz/sensors/logical_camera/Export.hh" +#include "gz/sensors/Sensor.hh" namespace ignition { diff --git a/include/gz/sensors/MagnetometerSensor.hh b/include/gz/sensors/MagnetometerSensor.hh index c2d9d841..feb41b1d 100644 --- a/include/gz/sensors/MagnetometerSensor.hh +++ b/include/gz/sensors/MagnetometerSensor.hh @@ -14,20 +14,20 @@ * limitations under the License. * */ -#ifndef IGNITION_SENSORS_MAGNETOMETERSENSOR_HH_ -#define IGNITION_SENSORS_MAGNETOMETERSENSOR_HH_ +#ifndef GZ_SENSORS_MAGNETOMETERSENSOR_HH_ +#define GZ_SENSORS_MAGNETOMETERSENSOR_HH_ #include #include -#include -#include +#include +#include -#include -#include +#include +#include -#include "ignition/sensors/Sensor.hh" +#include "gz/sensors/Sensor.hh" namespace ignition { diff --git a/include/gz/sensors/Manager.hh b/include/gz/sensors/Manager.hh index 5f52d38f..f818a38b 100644 --- a/include/gz/sensors/Manager.hh +++ b/include/gz/sensors/Manager.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_SENSORS_MANAGER_HH_ -#define IGNITION_SENSORS_MANAGER_HH_ +#ifndef GZ_SENSORS_MANAGER_HH_ +#define GZ_SENSORS_MANAGER_HH_ #include #include @@ -23,12 +23,12 @@ #include #include #include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sensors/NavSatSensor.hh b/include/gz/sensors/NavSatSensor.hh index 5781d826..a554792a 100644 --- a/include/gz/sensors/NavSatSensor.hh +++ b/include/gz/sensors/NavSatSensor.hh @@ -14,18 +14,18 @@ * limitations under the License. * */ -#ifndef IGNITION_SENSORS_NAVSAT_HH_ -#define IGNITION_SENSORS_NAVSAT_HH_ +#ifndef GZ_SENSORS_NAVSAT_HH_ +#define GZ_SENSORS_NAVSAT_HH_ #include -#include +#include #include -#include "ignition/sensors/config.hh" -#include "ignition/sensors/navsat/Export.hh" +#include "gz/sensors/config.hh" +#include "gz/sensors/navsat/Export.hh" -#include "ignition/sensors/Sensor.hh" +#include "gz/sensors/Sensor.hh" namespace ignition { diff --git a/include/gz/sensors/Noise.hh b/include/gz/sensors/Noise.hh index 405bfb79..a8086698 100644 --- a/include/gz/sensors/Noise.hh +++ b/include/gz/sensors/Noise.hh @@ -15,16 +15,16 @@ * */ -#ifndef IGNITION_SENSORS_NOISE_HH_ -#define IGNITION_SENSORS_NOISE_HH_ +#ifndef GZ_SENSORS_NOISE_HH_ +#define GZ_SENSORS_NOISE_HH_ #include #include #include -#include -#include -#include +#include +#include +#include #include @@ -37,7 +37,7 @@ namespace ignition // Forward declarations class NoisePrivate; - /// \class NoiseFactory Noise.hh ignition/sensors/Noise.hh + /// \class NoiseFactory Noise.hh gz/sensors/Noise.hh /// \brief Use this noise manager for creating and loading noise models. class IGNITION_SENSORS_VISIBLE NoiseFactory { @@ -70,7 +70,7 @@ namespace ignition GAUSSIAN = 2 }; - /// \class Noise Noise.hh ignition/sensors/Noise.hh + /// \class Noise Noise.hh gz/sensors/Noise.hh /// \brief Noise models for sensor output signals. class IGNITION_SENSORS_VISIBLE Noise { diff --git a/include/gz/sensors/RenderingEvents.hh b/include/gz/sensors/RenderingEvents.hh index 2ecc3eb8..04495021 100644 --- a/include/gz/sensors/RenderingEvents.hh +++ b/include/gz/sensors/RenderingEvents.hh @@ -15,11 +15,11 @@ * */ -#ifndef IGNITION_SENSORS_RENDERINGEVENTS_HH_ -#define IGNITION_SENSORS_RENDERINGEVENTS_HH_ +#ifndef GZ_SENSORS_RENDERINGEVENTS_HH_ +#define GZ_SENSORS_RENDERINGEVENTS_HH_ -#include -#include +#include +#include // TODO(louise) Remove these pragmas once ign-rendering is disabling the // warnings @@ -27,13 +27,13 @@ #pragma warning(push) #pragma warning(disable: 4251) #endif -#include +#include #ifdef _WIN32 #pragma warning(pop) #endif -#include -#include +#include +#include namespace ignition { diff --git a/include/gz/sensors/RenderingSensor.hh b/include/gz/sensors/RenderingSensor.hh index a3cc7a8a..af5dd482 100644 --- a/include/gz/sensors/RenderingSensor.hh +++ b/include/gz/sensors/RenderingSensor.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_SENSORS_RENDERINGSENSOR_HH_ -#define IGNITION_SENSORS_RENDERINGSENSOR_HH_ +#ifndef GZ_SENSORS_RENDERINGSENSOR_HH_ +#define GZ_SENSORS_RENDERINGSENSOR_HH_ #include -#include +#include // TODO(louise) Remove these pragmas once ign-rendering is disabling the // warnings @@ -27,13 +27,13 @@ #pragma warning(push) #pragma warning(disable: 4251) #endif -#include +#include #ifdef _WIN32 #pragma warning(pop) #endif -#include "ignition/sensors/rendering/Export.hh" -#include "ignition/sensors/Sensor.hh" +#include "gz/sensors/rendering/Export.hh" +#include "gz/sensors/Sensor.hh" namespace ignition { diff --git a/include/gz/sensors/RgbdCameraSensor.hh b/include/gz/sensors/RgbdCameraSensor.hh index 0b414502..282ad734 100644 --- a/include/gz/sensors/RgbdCameraSensor.hh +++ b/include/gz/sensors/RgbdCameraSensor.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_SENSORS_RGBDCAMERASENSOR_HH_ -#define IGNITION_SENSORS_RGBDCAMERASENSOR_HH_ +#ifndef GZ_SENSORS_RGBDCAMERASENSOR_HH_ +#define GZ_SENSORS_RGBDCAMERASENSOR_HH_ #include #include -#include +#include -#include "ignition/sensors/CameraSensor.hh" -#include "ignition/sensors/config.hh" -#include "ignition/sensors/rgbd_camera/Export.hh" -#include "ignition/sensors/Export.hh" +#include "gz/sensors/CameraSensor.hh" +#include "gz/sensors/config.hh" +#include "gz/sensors/rgbd_camera/Export.hh" +#include "gz/sensors/Export.hh" namespace ignition { diff --git a/include/gz/sensors/SegmentationCameraSensor.hh b/include/gz/sensors/SegmentationCameraSensor.hh index f10ac49d..5018d881 100644 --- a/include/gz/sensors/SegmentationCameraSensor.hh +++ b/include/gz/sensors/SegmentationCameraSensor.hh @@ -15,25 +15,25 @@ * */ -#ifndef IGNITION_SENSORS_SEGMENTATIONCAMERASENSOR_HH_ -#define IGNITION_SENSORS_SEGMENTATIONCAMERASENSOR_HH_ +#ifndef GZ_SENSORS_SEGMENTATIONCAMERASENSOR_HH_ +#define GZ_SENSORS_SEGMENTATIONCAMERASENSOR_HH_ #include #include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include #include -#include "ignition/sensors/CameraSensor.hh" -#include "ignition/sensors/Export.hh" -#include "ignition/sensors/Sensor.hh" +#include "gz/sensors/CameraSensor.hh" +#include "gz/sensors/Export.hh" +#include "gz/sensors/Sensor.hh" -#include "ignition/sensors/segmentation_camera/Export.hh" +#include "gz/sensors/segmentation_camera/Export.hh" namespace ignition { diff --git a/include/gz/sensors/Sensor.hh b/include/gz/sensors/Sensor.hh index df7307b1..d3a3204c 100644 --- a/include/gz/sensors/Sensor.hh +++ b/include/gz/sensors/Sensor.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_SENSORS_SENSOR_HH_ -#define IGNITION_SENSORS_SENSOR_HH_ +#ifndef GZ_SENSORS_SENSOR_HH_ +#define GZ_SENSORS_SENSOR_HH_ #ifdef _WIN32 #pragma warning(push) #pragma warning(disable: 4005) #pragma warning(disable: 4251) #endif -#include +#include #ifdef _WIN32 #pragma warning(pop) #endif @@ -31,10 +31,10 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include namespace ignition diff --git a/include/gz/sensors/SensorFactory.hh b/include/gz/sensors/SensorFactory.hh index 4845b0ad..1a4e9886 100644 --- a/include/gz/sensors/SensorFactory.hh +++ b/include/gz/sensors/SensorFactory.hh @@ -14,21 +14,21 @@ * limitations under the License. * */ -#ifndef IGNITION_SENSORS_SENSORFACTORY_HH_ -#define IGNITION_SENSORS_SENSORFACTORY_HH_ +#ifndef GZ_SENSORS_SENSORFACTORY_HH_ +#define GZ_SENSORS_SENSORFACTORY_HH_ #include #include #include #include -#include -#include +#include +#include -#include -#include +#include +#include -#include "ignition/sensors/Sensor.hh" +#include "gz/sensors/Sensor.hh" namespace ignition { diff --git a/include/gz/sensors/SensorTypes.hh b/include/gz/sensors/SensorTypes.hh index 0272df28..b66dc2a9 100644 --- a/include/gz/sensors/SensorTypes.hh +++ b/include/gz/sensors/SensorTypes.hh @@ -14,22 +14,22 @@ * limitations under the License. * */ -#ifndef IGNITION_SENSORS_SENSORTYPES_HH_ -#define IGNITION_SENSORS_SENSORTYPES_HH_ +#ifndef GZ_SENSORS_SENSORTYPES_HH_ +#define GZ_SENSORS_SENSORTYPES_HH_ #include #include -#include -#include -#include +#include +#include +#include /// \file -/// \ingroup ignition_sensors +/// \ingroup gz_sensors /// \brief Forward declarations and typedefs for sensors namespace ignition { - /// \ingroup ignition_sensors + /// \ingroup gz_sensors /// \brief Sensors namespace namespace sensors { diff --git a/include/gz/sensors/ThermalCameraSensor.hh b/include/gz/sensors/ThermalCameraSensor.hh index 2ec14959..009ce45e 100644 --- a/include/gz/sensors/ThermalCameraSensor.hh +++ b/include/gz/sensors/ThermalCameraSensor.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_SENSORS_THERMALCAMERASENSOR_HH_ -#define IGNITION_SENSORS_THERMALCAMERASENSOR_HH_ +#ifndef GZ_SENSORS_THERMALCAMERASENSOR_HH_ +#define GZ_SENSORS_THERMALCAMERASENSOR_HH_ #include #include @@ -23,15 +23,15 @@ #include -#include -#include +#include +#include #ifdef _WIN32 #pragma warning(push) #pragma warning(disable: 4005) #pragma warning(disable: 4251) #endif -#include +#include #ifdef _WIN32 #pragma warning(pop) #endif @@ -42,15 +42,15 @@ #pragma warning(push) #pragma warning(disable: 4251) #endif -#include +#include #ifdef _WIN32 #pragma warning(pop) #endif -#include "ignition/sensors/thermal_camera/Export.hh" -#include "ignition/sensors/CameraSensor.hh" -#include "ignition/sensors/Export.hh" -#include "ignition/sensors/Sensor.hh" +#include "gz/sensors/thermal_camera/Export.hh" +#include "gz/sensors/CameraSensor.hh" +#include "gz/sensors/Export.hh" +#include "gz/sensors/Sensor.hh" namespace ignition { diff --git a/include/gz/sensors/Util.hh b/include/gz/sensors/Util.hh index e9d2db43..30bd56f5 100644 --- a/include/gz/sensors/Util.hh +++ b/include/gz/sensors/Util.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_SENSORS_UTIL_HH_ -#define IGNITION_SENSORS_UTIL_HH_ +#ifndef GZ_SENSORS_UTIL_HH_ +#define GZ_SENSORS_UTIL_HH_ #include #include #include -#include "ignition/sensors/config.hh" -#include "ignition/sensors/Export.hh" +#include "gz/sensors/config.hh" +#include "gz/sensors/Export.hh" namespace ignition { diff --git a/include/gz/sensors/WideAngleCameraSensor.hh b/include/gz/sensors/WideAngleCameraSensor.hh index cf0689eb..960e7eb3 100644 --- a/include/gz/sensors/WideAngleCameraSensor.hh +++ b/include/gz/sensors/WideAngleCameraSensor.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_SENSORS_WIDEANGLECAMERASENSOR_HH_ -#define IGNITION_SENSORS_WIDEANGLECAMERASENSOR_HH_ +#ifndef GZ_SENSORS_WIDEANGLECAMERASENSOR_HH_ +#define GZ_SENSORS_WIDEANGLECAMERASENSOR_HH_ #include #include @@ -23,15 +23,15 @@ #include -#include -#include +#include +#include #ifdef _WIN32 #pragma warning(push) #pragma warning(disable: 4005) #pragma warning(disable: 4251) #endif -#include +#include #ifdef _WIN32 #pragma warning(pop) #endif @@ -42,15 +42,15 @@ #pragma warning(push) #pragma warning(disable: 4251) #endif -#include +#include #ifdef _WIN32 #pragma warning(pop) #endif -#include "ignition/sensors/wide_angle_camera/Export.hh" -#include "ignition/sensors/CameraSensor.hh" -#include "ignition/sensors/Export.hh" -#include "ignition/sensors/Sensor.hh" +#include "gz/sensors/wide_angle_camera/Export.hh" +#include "gz/sensors/CameraSensor.hh" +#include "gz/sensors/Export.hh" +#include "gz/sensors/Sensor.hh" namespace ignition { diff --git a/include/gz/sensors/sensors.hh.in b/include/gz/sensors/sensors.hh.in index 1c79666b..61b338de 100644 --- a/include/gz/sensors/sensors.hh.in +++ b/include/gz/sensors/sensors.hh.in @@ -1,3 +1,3 @@ // Automatically generated -#include +#include ${ign_headers}