From b28c2376532c48252e3418841df01e10622f51aa Mon Sep 17 00:00:00 2001 From: methylDragon Date: Fri, 17 Jun 2022 19:52:31 -0700 Subject: [PATCH] ign -> gz Upstream Macro Migration : gz-sensors (#232) --- CMakeLists.txt | 4 +-- Changelog.md | 2 +- Migration.md | 5 ++- examples/imu_noise/main.cc | 6 ++-- examples/loop_sensor/sensors.sdf | 2 +- examples/save_image/main.cc | 4 +-- include/gz/sensors/AirPressureSensor.hh | 4 +-- include/gz/sensors/AltimeterSensor.hh | 4 +-- include/gz/sensors/BrownDistortionModel.hh | 2 +- include/gz/sensors/CameraSensor.hh | 6 ++-- include/gz/sensors/DepthCameraSensor.hh | 6 ++-- include/gz/sensors/Distortion.hh | 2 +- include/gz/sensors/ForceTorqueSensor.hh | 4 +-- include/gz/sensors/GpuLidarSensor.hh | 4 +-- include/gz/sensors/ImuSensor.hh | 4 +-- include/gz/sensors/Lidar.hh | 8 ++--- include/gz/sensors/LogicalCameraSensor.hh | 4 +-- include/gz/sensors/MagnetometerSensor.hh | 4 +-- include/gz/sensors/Manager.hh | 4 +-- include/gz/sensors/NavSatSensor.hh | 4 +-- include/gz/sensors/RenderingEvents.hh | 4 +-- include/gz/sensors/RenderingSensor.hh | 6 ++-- include/gz/sensors/RgbdCameraSensor.hh | 8 ++--- .../gz/sensors/SegmentationCameraSensor.hh | 6 ++-- include/gz/sensors/Sensor.hh | 4 +-- include/gz/sensors/SensorFactory.hh | 4 +-- include/gz/sensors/ThermalCameraSensor.hh | 6 ++-- include/gz/sensors/Util.hh | 8 ++--- include/gz/sensors/WideAngleCameraSensor.hh | 6 ++-- src/AirPressureSensor.cc | 2 +- src/AltimeterSensor.cc | 2 +- src/CameraSensor.cc | 10 +++--- src/DepthCameraSensor.cc | 4 +-- src/Distortion.cc | 8 ++--- src/ForceTorqueSensor.cc | 2 +- src/GpuLidarSensor.cc | 6 ++-- src/ImageDistortion.cc | 8 ++--- src/ImageNoise.cc | 8 ++--- src/ImuSensor.cc | 14 ++++---- src/ImuSensor_TEST.cc | 36 +++++++++---------- src/Lidar.cc | 2 +- src/LogicalCameraSensor.cc | 2 +- src/MagnetometerSensor.cc | 2 +- src/Manager.cc | 2 +- src/NavSatSensor.cc | 6 ++-- src/Noise.cc | 8 ++--- src/RenderingSensor.cc | 2 +- src/RgbdCameraSensor.cc | 14 ++++---- src/SegmentationCameraSensor.cc | 4 +-- src/Sensor.cc | 2 +- src/SensorTypes.cc | 2 +- src/ThermalCameraSensor.cc | 4 +-- src/Util.cc | 19 +++++++--- src/Util_TEST.cc | 2 +- src/WideAngleCameraSensor.cc | 6 ++-- test/integration/force_torque.cc | 4 +-- test/integration/gpu_lidar_sensor.cc | 22 ++++++------ test/integration/navsat.cc | 8 ++--- test/sdf/custom_sensors.sdf | 6 ++-- tutorials/custom_sensors.md | 4 +-- tutorials/segmentation_camera.md | 2 +- 61 files changed, 186 insertions(+), 172 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4c208058..ab759d0b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -25,9 +25,9 @@ set (DRI_TESTS TRUE CACHE BOOL "True to enable DRI tests") option(ENABLE_PROFILER "Enable Gazebo Profiler" FALSE) if(ENABLE_PROFILER) - add_definitions("-DIGN_PROFILER_ENABLE=1") + add_definitions("-DGZ_PROFILER_ENABLE=1") else() - add_definitions("-DIGN_PROFILER_ENABLE=0") + add_definitions("-DGZ_PROFILER_ENABLE=0") endif() #============================================================================ diff --git a/Changelog.md b/Changelog.md index 2ccfce93..0bead0bb 100644 --- a/Changelog.md +++ b/Changelog.md @@ -371,7 +371,7 @@ ### Gazebo Sensors 2.5.0 -1. Add `IGN_PROFILER_ENABLE` cmake option for enabling the ign-common profiler. +1. Add `GZ_PROFILER_ENABLE` cmake option for enabling the ign-common profiler. * [BitBucket pull request 82](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-sensors/pull-requests/82) 1. Deduplicate `frame_ids` from sensor message headers diff --git a/Migration.md b/Migration.md index 1e663183..bd8c69f9 100644 --- a/Migration.md +++ b/Migration.md @@ -10,7 +10,10 @@ release will remove the deprecated code. 1. The `ignition` namespace is deprecated and will be removed in future versions. Use `gz` instead. 1. Header files under `ignition/...` are deprecated and will be removed in future versions. - Use `gz/...` instead. + Use `gz/...` instead. + +1. The `ignition:type` SDF attribute is deprecated and will be removed. + Please use `gz:type` instead. 1. **CameraSensor**: the default anti-aliasing value has changed from `2` to `4`. diff --git a/examples/imu_noise/main.cc b/examples/imu_noise/main.cc index 3e9288e9..ce552ec5 100644 --- a/examples/imu_noise/main.cc +++ b/examples/imu_noise/main.cc @@ -34,13 +34,13 @@ static constexpr double kNumSamples = 6 * 3600 * kSampleFrequency; // These values come from the Rotors default values: // https://github.com/ethz-asl/rotors_simulator/blob/513bb92da0c1a0c968bdc679dffc8fe7d77de918/rotors_gazebo_plugins/include/rotors_gazebo_plugins/gazebo_imu_plugin.h#L40 static constexpr double kDefaultAdisGyroscopeNoiseDensity = - 2.0 * 35.0 / 3600.0 / 180.0 * IGN_PI; + 2.0 * 35.0 / 3600.0 / 180.0 * GZ_PI; static constexpr double kDefaultAdisGyroscopeRandomWalk = - 2.0 * 4.0 / 3600.0 / 180.0 * IGN_PI; + 2.0 * 4.0 / 3600.0 / 180.0 * GZ_PI; static constexpr double kDefaultAdisGyroscopeBiasCorrelationTime = 1.0e+3; static constexpr double kDefaultAdisGyroscopeTurnOnBiasSigma = - 0.5 / 180.0 * IGN_PI; + 0.5 / 180.0 * GZ_PI; static constexpr double kDefaultAdisAccelerometerNoiseDensity = 2.0 * 2.0e-3; static constexpr double kDefaultAdisAccelerometerRandomWalk = diff --git a/examples/loop_sensor/sensors.sdf b/examples/loop_sensor/sensors.sdf index a52827f4..415c10c1 100644 --- a/examples/loop_sensor/sensors.sdf +++ b/examples/loop_sensor/sensors.sdf @@ -22,7 +22,7 @@ - + 1 30 odometer diff --git a/examples/save_image/main.cc b/examples/save_image/main.cc index f5e5643a..53af2274 100644 --- a/examples/save_image/main.cc +++ b/examples/save_image/main.cc @@ -86,7 +86,7 @@ int main() const double hz = 30; const std::size_t width = 480; const std::size_t height = 320; - const std::size_t hfov = IGN_DTOR(60); + const std::size_t hfov = GZ_DTOR(60); const double near = 0.1; const double far = 100; const auto format = sdf::PixelFormatType::RGB_INT8; @@ -202,7 +202,7 @@ void BuildScene(gz::rendering::ScenePtr _scene) box->AddGeometry(_scene->CreateBox()); box->SetOrigin(0.0, 0.5, 0.0); box->SetLocalPosition(3, 0, 0); - box->SetLocalRotation(IGN_PI / 4, 0, IGN_PI / 3); + box->SetLocalRotation(GZ_PI / 4, 0, GZ_PI / 3); box->SetLocalScale(1, 2.5, 1); box->SetMaterial(blue); root->AddChild(box); diff --git a/include/gz/sensors/AirPressureSensor.hh b/include/gz/sensors/AirPressureSensor.hh index 6f0eb48b..d52fa882 100644 --- a/include/gz/sensors/AirPressureSensor.hh +++ b/include/gz/sensors/AirPressureSensor.hh @@ -85,11 +85,11 @@ namespace gz /// \todo(iche033) Make this function virtual on Garden public: bool HasConnections() const; - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/gz/sensors/AltimeterSensor.hh b/include/gz/sensors/AltimeterSensor.hh index c12220c7..cdb4e510 100644 --- a/include/gz/sensors/AltimeterSensor.hh +++ b/include/gz/sensors/AltimeterSensor.hh @@ -102,11 +102,11 @@ namespace gz /// \todo(iche033) Make this function virtual on Garden public: bool HasConnections() const; - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/gz/sensors/BrownDistortionModel.hh b/include/gz/sensors/BrownDistortionModel.hh index 7a68a1ed..86c9bb4e 100644 --- a/include/gz/sensors/BrownDistortionModel.hh +++ b/include/gz/sensors/BrownDistortionModel.hh @@ -78,7 +78,7 @@ namespace gz public: virtual void Print(std::ostream &_out) const override; /// \brief Private data pointer. - IGN_UTILS_IMPL_PTR(dataPtr) + GZ_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/gz/sensors/CameraSensor.hh b/include/gz/sensors/CameraSensor.hh index 5dce6568..c9a525b3 100644 --- a/include/gz/sensors/CameraSensor.hh +++ b/include/gz/sensors/CameraSensor.hh @@ -63,7 +63,7 @@ namespace gz /// \brief Camera Sensor Class /// - /// This class creates images from an ignition rendering scene. The scene + /// This class creates images from a Gazebo Rendering scene. The scene /// must be created in advance and given to Manager::Init(). /// It offers both an ignition-transport interface and a direct C++ API /// to access the image data. The API works by setting a callback to be @@ -175,11 +175,11 @@ namespace gz /// \param[in] _scene Pointer to the new scene. private: void OnSceneChange(gz::rendering::ScenePtr /*_scene*/); - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/gz/sensors/DepthCameraSensor.hh b/include/gz/sensors/DepthCameraSensor.hh index e994e539..672cd459 100644 --- a/include/gz/sensors/DepthCameraSensor.hh +++ b/include/gz/sensors/DepthCameraSensor.hh @@ -63,7 +63,7 @@ namespace gz /// \brief Depth camera sensor class. /// - /// This class creates depth image from an ignition rendering scene. + /// This class creates depth image from a Gazebo Rendering scene. /// The scene must be created in advance and given to Manager::Init(). /// It offers both an ignition-transport interface and a direct C++ API /// to access the image data. The API works by setting a callback to be @@ -171,11 +171,11 @@ namespace gz private: void OnSceneChange(gz::rendering::ScenePtr /*_scene*/) { } - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/gz/sensors/Distortion.hh b/include/gz/sensors/Distortion.hh index ad166acd..53e4af3a 100644 --- a/include/gz/sensors/Distortion.hh +++ b/include/gz/sensors/Distortion.hh @@ -100,7 +100,7 @@ namespace gz public: virtual void Print(std::ostream &_out) const; /// \brief Private data pointer - IGN_UTILS_IMPL_PTR(dataPtr) + GZ_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/gz/sensors/ForceTorqueSensor.hh b/include/gz/sensors/ForceTorqueSensor.hh index e240a555..e0d3adbf 100644 --- a/include/gz/sensors/ForceTorqueSensor.hh +++ b/include/gz/sensors/ForceTorqueSensor.hh @@ -120,11 +120,11 @@ namespace gz /// \todo(iche033) Make this function virtual on Garden public: bool HasConnections() const; - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/gz/sensors/GpuLidarSensor.hh b/include/gz/sensors/GpuLidarSensor.hh index 86733cd8..3712fb72 100644 --- a/include/gz/sensors/GpuLidarSensor.hh +++ b/include/gz/sensors/GpuLidarSensor.hh @@ -139,11 +139,11 @@ namespace gz unsigned int _heighti, unsigned int _channels, const std::string &_format); - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/gz/sensors/ImuSensor.hh b/include/gz/sensors/ImuSensor.hh index 25c1dcbe..0db84a73 100644 --- a/include/gz/sensors/ImuSensor.hh +++ b/include/gz/sensors/ImuSensor.hh @@ -171,11 +171,11 @@ namespace gz /// \todo(iche033) Make this function virtual on Garden public: bool HasConnections() const; - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/gz/sensors/Lidar.hh b/include/gz/sensors/Lidar.hh index cdccfe50..3e789460 100644 --- a/include/gz/sensors/Lidar.hh +++ b/include/gz/sensors/Lidar.hh @@ -245,10 +245,10 @@ namespace gz /// \return Visibility mask public: uint32_t VisibilityMask() const; - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Just a mutex for thread safety public: mutable std::mutex lidarMutex; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING /// \brief Raw buffer of laser data. public: float *laserBuffer = nullptr; @@ -268,11 +268,11 @@ namespace gz unsigned int _heighti, unsigned int _channels, const std::string &/*_format*/)> _subscriber); - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/gz/sensors/LogicalCameraSensor.hh b/include/gz/sensors/LogicalCameraSensor.hh index 7dec282c..a5f845de 100644 --- a/include/gz/sensors/LogicalCameraSensor.hh +++ b/include/gz/sensors/LogicalCameraSensor.hh @@ -118,11 +118,11 @@ namespace gz /// \return List of detected models. public: msgs::LogicalCameraImage Image() const; - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/gz/sensors/MagnetometerSensor.hh b/include/gz/sensors/MagnetometerSensor.hh index 60064205..592cf0d9 100644 --- a/include/gz/sensors/MagnetometerSensor.hh +++ b/include/gz/sensors/MagnetometerSensor.hh @@ -98,11 +98,11 @@ namespace gz /// \todo(iche033) Make this function virtual on Garden public: bool HasConnections() const; - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/gz/sensors/Manager.hh b/include/gz/sensors/Manager.hh index 3586f7bc..a71e68d1 100644 --- a/include/gz/sensors/Manager.hh +++ b/include/gz/sensors/Manager.hh @@ -139,10 +139,10 @@ namespace gz /// \brief Adds colon delimited paths sensor plugins may be public: void GZ_DEPRECATED(6) AddPluginPaths(const std::string &_path); - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief private data pointer private: std::unique_ptr dataPtr; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/gz/sensors/NavSatSensor.hh b/include/gz/sensors/NavSatSensor.hh index 6ce12a9f..0f998d0d 100644 --- a/include/gz/sensors/NavSatSensor.hh +++ b/include/gz/sensors/NavSatSensor.hh @@ -120,11 +120,11 @@ namespace gz public: void SetPosition(const math::Angle &_latitude, const math::Angle &_longitude, double _altitude = 0.0); - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/gz/sensors/RenderingEvents.hh b/include/gz/sensors/RenderingEvents.hh index 77a972d4..424b0fc1 100644 --- a/include/gz/sensors/RenderingEvents.hh +++ b/include/gz/sensors/RenderingEvents.hh @@ -55,12 +55,12 @@ namespace gz std::function _callback); - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Event that is used to trigger callbacks when the scene /// is changed public: static gz::common::EventT< void(const gz::rendering::ScenePtr &)> sceneEvent; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/gz/sensors/RenderingSensor.hh b/include/gz/sensors/RenderingSensor.hh index 5d2d9428..0f236701 100644 --- a/include/gz/sensors/RenderingSensor.hh +++ b/include/gz/sensors/RenderingSensor.hh @@ -48,7 +48,7 @@ namespace gz /// \brief a rendering sensor class /// /// This class is a base for all rendering sensor classes. It provides - /// interface to ignition rendering objects + /// interface to Gazebo Rendering objects class GZ_SENSORS_RENDERING_VISIBLE RenderingSensor : public Sensor { @@ -86,11 +86,11 @@ namespace gz /// \param[in] _sensor Sensor to add. protected: void AddSensor(rendering::SensorPtr _sensor); - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \internal /// \brief Data pointer for private data private: std::unique_ptr dataPtr; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/gz/sensors/RgbdCameraSensor.hh b/include/gz/sensors/RgbdCameraSensor.hh index 54363c18..37442e32 100644 --- a/include/gz/sensors/RgbdCameraSensor.hh +++ b/include/gz/sensors/RgbdCameraSensor.hh @@ -39,8 +39,8 @@ namespace gz /// \brief RGBD camera sensor class. /// - /// This class creates a few types of sensor data from an ignition - /// rendering scene: + /// This class creates a few types of sensor data from a Gazebo + /// Rendering scene: /// * RGB image (same as CameraSensor) /// * Depth image (same as DepthCamera) /// * (future / todo) Color point cloud @@ -99,11 +99,11 @@ namespace gz /// \return True on success. private: bool CreateCameras(); - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/gz/sensors/SegmentationCameraSensor.hh b/include/gz/sensors/SegmentationCameraSensor.hh index 0141b550..b385e4b4 100644 --- a/include/gz/sensors/SegmentationCameraSensor.hh +++ b/include/gz/sensors/SegmentationCameraSensor.hh @@ -45,7 +45,7 @@ namespace gz /// \brief Segmentation camera sensor class. /// - /// This class creates segmentation images from an ignition rendering scene. + /// This class creates segmentation images from a Gazebo Rendering scene. /// The scene must be created in advance and given to Manager::Init(). /// It offers both an ignition-transport interface and a direct C++ API /// to access the image data. The API works by setting a callback to be @@ -126,11 +126,11 @@ namespace gz /// \return True on success. private: bool CreateCamera(); - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/gz/sensors/Sensor.hh b/include/gz/sensors/Sensor.hh index 1a08cb96..355cbfc7 100644 --- a/include/gz/sensors/Sensor.hh +++ b/include/gz/sensors/Sensor.hh @@ -227,11 +227,11 @@ namespace gz /// \sa IsActive public: void SetActive(bool _active); - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \internal /// \brief Data pointer for private data private: std::unique_ptr dataPtr; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/gz/sensors/SensorFactory.hh b/include/gz/sensors/SensorFactory.hh index a459841f..b7d8175c 100644 --- a/include/gz/sensors/SensorFactory.hh +++ b/include/gz/sensors/SensorFactory.hh @@ -190,10 +190,10 @@ namespace gz /// \deprecated Sensor plugins aren't supported anymore. public: void GZ_DEPRECATED(6) AddPluginPaths(const std::string &_path); - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief private data pointer private: std::unique_ptr dataPtr; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/gz/sensors/ThermalCameraSensor.hh b/include/gz/sensors/ThermalCameraSensor.hh index b9fde8bc..c6236894 100644 --- a/include/gz/sensors/ThermalCameraSensor.hh +++ b/include/gz/sensors/ThermalCameraSensor.hh @@ -63,7 +63,7 @@ namespace gz /// \brief Thermal camera sensor class. /// - /// This class creates thermal image from an ignition rendering scene. + /// This class creates thermal image from a Gazebo Rendering scene. /// The scene must be created in advance and given to Manager::Init(). /// It offers both an ignition-transport interface and a direct C++ API /// to access the image data. The API works by setting a callback to be @@ -175,11 +175,11 @@ namespace gz private: void OnSceneChange(gz::rendering::ScenePtr /*_scene*/) { } - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/gz/sensors/Util.hh b/include/gz/sensors/Util.hh index 03a9b62e..ccc3b919 100644 --- a/include/gz/sensors/Util.hh +++ b/include/gz/sensors/Util.hh @@ -36,12 +36,12 @@ inline namespace GZ_SENSORS_VERSION_NAMESPACE { /// /// Given an SDF tag as follows: /// -/// +/// /// /// This function returns `sensor_type`. /// /// It will return an empty string if the element is malformed. For example, -/// if it misses the `ignition:type` attribute or is not of `type="custom"`. +/// if it misses the `gz:type` attribute or is not of `type="custom"`. /// /// \param[in] _sdf Sensor SDF object. /// \return _sensorType Name of sensor type. @@ -51,12 +51,12 @@ std::string GZ_SENSORS_VISIBLE customType(const sdf::Sensor &_sdf); // NOLINT /// /// Given an SDF tag as follows: /// -/// +/// /// /// This function returns `sensor_type`. /// /// It will return an empty string if the element is malformed. For example, -/// if it misses the `ignition:type` attribute or is not of `type="custom"`. +/// if it misses the `gz:type` attribute or is not of `type="custom"`. /// /// \param[in] _sdf Sensor SDF object. /// \return _sensorType Name of sensor type. diff --git a/include/gz/sensors/WideAngleCameraSensor.hh b/include/gz/sensors/WideAngleCameraSensor.hh index b3bd9ede..446b9b85 100644 --- a/include/gz/sensors/WideAngleCameraSensor.hh +++ b/include/gz/sensors/WideAngleCameraSensor.hh @@ -63,7 +63,7 @@ namespace gz /// \brief Wide Angle camera sensor class. /// - /// This class creates wide angle camera image from an ignition rendering + /// This class creates wide angle camera image from a Gazebo Rendering /// scene. The scene must be created in advance and given to Manager::Init() /// It offers both an ignition-transport interface and a direct C++ API /// to access the image data. The API works by setting a callback to be @@ -149,11 +149,11 @@ namespace gz private: void OnSceneChange(gz::rendering::ScenePtr /*_scene*/) { } - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/src/AirPressureSensor.cc b/src/AirPressureSensor.cc index 0399a743..851bb230 100644 --- a/src/AirPressureSensor.cc +++ b/src/AirPressureSensor.cc @@ -148,7 +148,7 @@ bool AirPressureSensor::Load(sdf::ElementPtr _sdf) bool AirPressureSensor::Update( const std::chrono::steady_clock::duration &_now) { - IGN_PROFILE("AirPressureSensor::Update"); + GZ_PROFILE("AirPressureSensor::Update"); if (!this->dataPtr->initialized) { gzerr << "Not initialized, update ignored.\n"; diff --git a/src/AltimeterSensor.cc b/src/AltimeterSensor.cc index 72717c7d..02088971 100644 --- a/src/AltimeterSensor.cc +++ b/src/AltimeterSensor.cc @@ -135,7 +135,7 @@ bool AltimeterSensor::Load(sdf::ElementPtr _sdf) ////////////////////////////////////////////////// bool AltimeterSensor::Update(const std::chrono::steady_clock::duration &_now) { - IGN_PROFILE("AltimeterSensor::Update"); + GZ_PROFILE("AltimeterSensor::Update"); if (!this->dataPtr->initialized) { gzerr << "Not initialized, update ignored.\n"; diff --git a/src/CameraSensor.cc b/src/CameraSensor.cc index e611ab5f..63e01db6 100644 --- a/src/CameraSensor.cc +++ b/src/CameraSensor.cc @@ -190,7 +190,7 @@ bool CameraSensor::CreateCamera() this->dataPtr->camera->SetAntiAliasing(cameraSdf->AntiAliasingValue()); math::Angle angle = cameraSdf->HorizontalFov(); - if (angle < 0.01 || angle > IGN_PI*2) + if (angle < 0.01 || angle > GZ_PI*2) { gzerr << "Invalid horizontal field of view [" << angle << "]\n"; @@ -373,7 +373,7 @@ void CameraSensor::SetScene(gz::rendering::ScenePtr _scene) ////////////////////////////////////////////////// bool CameraSensor::Update(const std::chrono::steady_clock::duration &_now) { - IGN_PROFILE("CameraSensor::Update"); + GZ_PROFILE("CameraSensor::Update"); if (!this->dataPtr->initialized) { gzerr << "Not initialized, update ignored.\n"; @@ -424,7 +424,7 @@ bool CameraSensor::Update(const std::chrono::steady_clock::duration &_now) // generate sensor data this->Render(); { - IGN_PROFILE("CameraSensor::Update Copy image"); + GZ_PROFILE("CameraSensor::Update Copy image"); this->dataPtr->camera->Copy(this->dataPtr->image); } @@ -460,7 +460,7 @@ bool CameraSensor::Update(const std::chrono::steady_clock::duration &_now) // create message gz::msgs::Image msg; { - IGN_PROFILE("CameraSensor::Update Message"); + GZ_PROFILE("CameraSensor::Update Message"); msg.set_width(width); msg.set_height(height); msg.set_step(width * rendering::PixelUtil::BytesPerPixel( @@ -476,7 +476,7 @@ bool CameraSensor::Update(const std::chrono::steady_clock::duration &_now) // publish the image message { this->AddSequence(msg.mutable_header()); - IGN_PROFILE("CameraSensor::Update Publish"); + GZ_PROFILE("CameraSensor::Update Publish"); this->dataPtr->pub.Publish(msg); // publish the camera info message diff --git a/src/DepthCameraSensor.cc b/src/DepthCameraSensor.cc index 9700bb61..e00b0087 100644 --- a/src/DepthCameraSensor.cc +++ b/src/DepthCameraSensor.cc @@ -389,7 +389,7 @@ bool DepthCameraSensor::CreateCamera() this->dataPtr->depthCamera->SetAntiAliasing(2); math::Angle angle = cameraSdf->HorizontalFov(); - if (angle < 0.01 || angle > IGN_PI*2) + if (angle < 0.01 || angle > GZ_PI*2) { gzerr << "Invalid horizontal field of view [" << angle << "]\n"; @@ -514,7 +514,7 @@ void DepthCameraSensor::SetScene(gz::rendering::ScenePtr _scene) bool DepthCameraSensor::Update( const std::chrono::steady_clock::duration &_now) { - IGN_PROFILE("DepthCameraSensor::Update"); + GZ_PROFILE("DepthCameraSensor::Update"); if (!this->dataPtr->initialized) { gzerr << "Not initialized, update ignored.\n"; diff --git a/src/Distortion.cc b/src/Distortion.cc index d81d01cb..f75d46bf 100644 --- a/src/Distortion.cc +++ b/src/Distortion.cc @@ -62,7 +62,7 @@ DistortionPtr DistortionFactory::NewDistortionModel(const sdf::Camera &_sdf, else distortion.reset(new BrownDistortionModel()); - IGN_ASSERT(distortion->Type() == DistortionType::BROWN, + GZ_ASSERT(distortion->Type() == DistortionType::BROWN, "Distortion type should be 'brown'"); } else if (distortionType == DistortionType::NONE) @@ -71,7 +71,7 @@ DistortionPtr DistortionFactory::NewDistortionModel(const sdf::Camera &_sdf, // if 'custom', the type will be set once the user calls the // SetCustomDistortionCallback function. distortion.reset(new Distortion(DistortionType::NONE)); - IGN_ASSERT(distortion->Type() == DistortionType::NONE, + GZ_ASSERT(distortion->Type() == DistortionType::NONE, "Distortion type should be 'none'"); } else @@ -90,8 +90,8 @@ DistortionPtr DistortionFactory::NewDistortionModel(sdf::ElementPtr _sdf, { // TODO(WilliamLewww): create a distortion SDF to support different // distortion models - IGN_ASSERT(_sdf != nullptr, "camera sdf is null"); - IGN_ASSERT(_sdf->GetName() == "camera", "Not a camera SDF element"); + GZ_ASSERT(_sdf != nullptr, "camera sdf is null"); + GZ_ASSERT(_sdf->GetName() == "camera", "Not a camera SDF element"); sdf::Camera cameraDom; cameraDom.Load(_sdf); diff --git a/src/ForceTorqueSensor.cc b/src/ForceTorqueSensor.cc index 6bdada02..796c1936 100644 --- a/src/ForceTorqueSensor.cc +++ b/src/ForceTorqueSensor.cc @@ -170,7 +170,7 @@ bool ForceTorqueSensor::Load(sdf::ElementPtr _sdf) ////////////////////////////////////////////////// bool ForceTorqueSensor::Update(const std::chrono::steady_clock::duration &_now) { - IGN_PROFILE("ForceTorqueSensor::Update"); + GZ_PROFILE("ForceTorqueSensor::Update"); if (!this->dataPtr->initialized) { gzerr << "Not initialized, update ignored.\n"; diff --git a/src/GpuLidarSensor.cc b/src/GpuLidarSensor.cc index 3adfe423..05c26a82 100644 --- a/src/GpuLidarSensor.cc +++ b/src/GpuLidarSensor.cc @@ -263,7 +263,7 @@ void GpuLidarSensor::OnNewLidarFrame(const float *_data, ////////////////////////////////////////////////// bool GpuLidarSensor::Update(const std::chrono::steady_clock::duration &_now) { - IGN_PROFILE("GpuLidarSensor::Update"); + GZ_PROFILE("GpuLidarSensor::Update"); if (!this->initialized) { gzerr << "Not initialized, update ignored.\n"; @@ -306,7 +306,7 @@ bool GpuLidarSensor::Update(const std::chrono::steady_clock::duration &_now) { this->AddSequence(this->dataPtr->pointMsg.mutable_header()); - IGN_PROFILE("GpuLidarSensor::Update Publish point cloud"); + GZ_PROFILE("GpuLidarSensor::Update Publish point cloud"); this->dataPtr->pointPub.Publish(this->dataPtr->pointMsg); } } @@ -357,7 +357,7 @@ bool GpuLidarSensor::HasConnections() const ////////////////////////////////////////////////// void GpuLidarSensorPrivate::FillPointCloudMsg(const float *_laserBuffer) { - IGN_PROFILE("GpuLidarSensorPrivate::FillPointCloudMsg"); + GZ_PROFILE("GpuLidarSensorPrivate::FillPointCloudMsg"); uint32_t width = this->pointMsg.width(); uint32_t height = this->pointMsg.height(); unsigned int channels = 3; diff --git a/src/ImageDistortion.cc b/src/ImageDistortion.cc index 9c1d5d53..fa951862 100644 --- a/src/ImageDistortion.cc +++ b/src/ImageDistortion.cc @@ -48,7 +48,7 @@ DistortionPtr ImageDistortionFactory::NewDistortionModel( else distortion.reset(new BrownDistortionModel()); - IGN_ASSERT(distortion->Type() == DistortionType::BROWN, + GZ_ASSERT(distortion->Type() == DistortionType::BROWN, "Distortion type should be 'brown'"); } else if (distortionType == DistortionType::NONE) @@ -57,7 +57,7 @@ DistortionPtr ImageDistortionFactory::NewDistortionModel( // if 'custom', the type will be set once the user calls the // SetCustomDistortionCallback function. distortion.reset(new Distortion(DistortionType::NONE)); - IGN_ASSERT(distortion->Type() == DistortionType::NONE, + GZ_ASSERT(distortion->Type() == DistortionType::NONE, "Distortion type should be 'none'"); } else @@ -76,8 +76,8 @@ DistortionPtr ImageDistortionFactory::NewDistortionModel(sdf::ElementPtr _sdf, { // TODO(WilliamLewww): create a distortion SDF to support different // distortion models - IGN_ASSERT(_sdf != nullptr, "camera sdf is null"); - IGN_ASSERT(_sdf->GetName() == "camera", "Not a camera SDF element"); + GZ_ASSERT(_sdf != nullptr, "camera sdf is null"); + GZ_ASSERT(_sdf->GetName() == "camera", "Not a camera SDF element"); sdf::Camera cameraDom; cameraDom.Load(_sdf); diff --git a/src/ImageNoise.cc b/src/ImageNoise.cc index 4ffb6fc7..7f350982 100644 --- a/src/ImageNoise.cc +++ b/src/ImageNoise.cc @@ -51,7 +51,7 @@ NoisePtr ImageNoiseFactory::NewNoiseModel(const sdf::Noise &_sdf, else noise.reset(new GaussianNoiseModel()); - IGN_ASSERT(noise->Type() == NoiseType::GAUSSIAN, + GZ_ASSERT(noise->Type() == NoiseType::GAUSSIAN, "Noise type should be 'gaussian'"); } else if (noiseType == sdf::NoiseType::NONE) @@ -60,7 +60,7 @@ NoisePtr ImageNoiseFactory::NewNoiseModel(const sdf::Noise &_sdf, // if 'custom', the type will be set once the user calls the // SetCustomNoiseCallback function. noise.reset(new Noise(NoiseType::NONE)); - IGN_ASSERT(noise->Type() == NoiseType::NONE, + GZ_ASSERT(noise->Type() == NoiseType::NONE, "Noise type should be 'none'"); } else @@ -77,8 +77,8 @@ NoisePtr ImageNoiseFactory::NewNoiseModel(const sdf::Noise &_sdf, NoisePtr ImageNoiseFactory::NewNoiseModel(sdf::ElementPtr _sdf, const std::string &_sensorType) { - IGN_ASSERT(_sdf != nullptr, "noise sdf is null"); - IGN_ASSERT(_sdf->GetName() == "noise", "Not a noise SDF element"); + GZ_ASSERT(_sdf != nullptr, "noise sdf is null"); + GZ_ASSERT(_sdf->GetName() == "noise", "Not a noise SDF element"); sdf::Noise noiseDom; noiseDom.Load(_sdf); diff --git a/src/ImuSensor.cc b/src/ImuSensor.cc index 2653dc63..3fce17d7 100644 --- a/src/ImuSensor.cc +++ b/src/ImuSensor.cc @@ -200,7 +200,7 @@ bool ImuSensor::Load(sdf::ElementPtr _sdf) ////////////////////////////////////////////////// bool ImuSensor::Update(const std::chrono::steady_clock::duration &_now) { - IGN_PROFILE("ImuSensor::Update"); + GZ_PROFILE("ImuSensor::Update"); if (!this->dataPtr->initialized) { gzerr << "Not initialized, update ignored.\n"; @@ -344,25 +344,25 @@ void ImuSensor::SetWorldFrameOrientation( { {WorldFrameEnumType::ENU, gz::math::Quaterniond(0, 0, 0)}, {WorldFrameEnumType::NED, gz::math::Quaterniond( - IGN_PI, 0, IGN_PI/2)}, + GZ_PI, 0, GZ_PI/2)}, {WorldFrameEnumType::NWU, gz::math::Quaterniond( - 0, 0, IGN_PI/2)}, + 0, 0, GZ_PI/2)}, } }, {WorldFrameEnumType::NED, { {WorldFrameEnumType::ENU, gz::math::Quaterniond( - IGN_PI, 0, IGN_PI/2).Inverse()}, + GZ_PI, 0, GZ_PI/2).Inverse()}, {WorldFrameEnumType::NED, gz::math::Quaterniond(0, 0, 0)}, {WorldFrameEnumType::NWU, gz::math::Quaterniond( - -IGN_PI, 0, 0)}, + -GZ_PI, 0, 0)}, } }, {WorldFrameEnumType::NWU, { {WorldFrameEnumType::ENU, gz::math::Quaterniond( - 0, 0, -IGN_PI/2)}, - {WorldFrameEnumType::NED, gz::math::Quaterniond(IGN_PI, 0, 0)}, + 0, 0, -GZ_PI/2)}, + {WorldFrameEnumType::NED, gz::math::Quaterniond(GZ_PI, 0, 0)}, {WorldFrameEnumType::NWU, gz::math::Quaterniond(0, 0, 0)}, } } diff --git a/src/ImuSensor_TEST.cc b/src/ImuSensor_TEST.cc index bd166296..4ccfe5a4 100644 --- a/src/ImuSensor_TEST.cc +++ b/src/ImuSensor_TEST.cc @@ -39,13 +39,13 @@ using namespace gz; // These values come from the Rotors default values: // https://github.com/ethz-asl/rotors_simulator/blob/513bb92da0c1a0c968bdc679dffc8fe7d77de918/rotors_gazebo_plugins/include/rotors_gazebo_plugins/gazebo_imu_plugin.h#L40 static constexpr double kDefaultAdisGyroscopeNoiseDensity = - 2.0 * 35.0 / 3600.0 / 180.0 * IGN_PI; + 2.0 * 35.0 / 3600.0 / 180.0 * GZ_PI; static constexpr double kDefaultAdisGyroscopeRandomWalk = - 2.0 * 4.0 / 3600.0 / 180.0 * IGN_PI; + 2.0 * 4.0 / 3600.0 / 180.0 * GZ_PI; static constexpr double kDefaultAdisGyroscopeBiasCorrelationTime = 1.0e+3; static constexpr double kDefaultAdisGyroscopeTurnOnBiasSigma = - 0.5 / 180.0 * IGN_PI; + 0.5 / 180.0 * GZ_PI; static constexpr double kDefaultAdisAccelerometerNoiseDensity = 2.0 * 2.0e-3; static constexpr double kDefaultAdisAccelerometerRandomWalk = @@ -341,7 +341,7 @@ TEST(ImuSensor_TEST, Orientation) ASSERT_NE(nullptr, sensor); math::Quaterniond orientRef; - math::Quaterniond orientValue(math::Vector3d(IGN_PI/2.0, 0, IGN_PI)); + math::Quaterniond orientValue(math::Vector3d(GZ_PI/2.0, 0, GZ_PI)); math::Pose3d pose(math::Vector3d(0, 1, 2), orientValue); sensor->SetOrientationReference(orientRef); @@ -356,7 +356,7 @@ TEST(ImuSensor_TEST, Orientation) EXPECT_EQ(orientValue, sensor->Orientation()); // update pose and check orientation - math::Quaterniond newOrientValue(math::Vector3d(IGN_PI, IGN_PI/2, IGN_PI)); + math::Quaterniond newOrientValue(math::Vector3d(GZ_PI, GZ_PI/2, GZ_PI)); math::Pose3d newPose(math::Vector3d(0, 1, 1), newOrientValue); sensor->SetWorldPose(newPose); @@ -376,7 +376,7 @@ TEST(ImuSensor_TEST, Orientation) // update world pose with orientation disabled and verify that orientation // does not change - math::Quaterniond newOrientValue2(math::Vector3d(IGN_PI/2, IGN_PI/2, IGN_PI)); + math::Quaterniond newOrientValue2(math::Vector3d(GZ_PI/2, GZ_PI/2, GZ_PI)); math::Pose3d newPose2(math::Vector3d(1, 1, 0), newOrientValue2); sensor->SetWorldPose(newPose2); sensor->Update(std::chrono::steady_clock::duration( @@ -584,10 +584,10 @@ TEST(ImuSensor_TEST, NamedFrameOrientationReference) // Case A.2 Localization ref: ENU, World : ENU + rotation offset { - const math::Quaterniond worldFrameOrientation(0, 0, IGN_PI/4); + const math::Quaterniond worldFrameOrientation(0, 0, GZ_PI/4); const sensors::WorldFrameEnumType worldRelativeTo = sensors::WorldFrameEnumType::ENU; - const math::Quaterniond expectedSensorOrientation(0, 0, -IGN_PI/4); + const math::Quaterniond expectedSensorOrientation(0, 0, -GZ_PI/4); sensorENU->SetWorldFrameOrientation(worldFrameOrientation, worldRelativeTo); @@ -602,7 +602,7 @@ TEST(ImuSensor_TEST, NamedFrameOrientationReference) const math::Quaterniond worldFrameOrientation(0, 0, 0); const sensors::WorldFrameEnumType worldRelativeTo = sensors::WorldFrameEnumType::NWU; - const math::Quaterniond expectedSensorOrientation(0, 0, IGN_PI/2); + const math::Quaterniond expectedSensorOrientation(0, 0, GZ_PI/2); sensorENU->SetWorldFrameOrientation(worldFrameOrientation, worldRelativeTo); @@ -617,7 +617,7 @@ TEST(ImuSensor_TEST, NamedFrameOrientationReference) const math::Quaterniond worldFrameOrientation(0, 0, 0); const sensors::WorldFrameEnumType worldRelativeTo = sensors::WorldFrameEnumType::NED; - const math::Quaterniond expectedSensorOrientation(IGN_PI, 0, IGN_PI/2); + const math::Quaterniond expectedSensorOrientation(GZ_PI, 0, GZ_PI/2); sensorENU->SetWorldFrameOrientation(worldFrameOrientation, worldRelativeTo); @@ -649,10 +649,10 @@ TEST(ImuSensor_TEST, NamedFrameOrientationReference) // Case B.2 : Localization ref: NWU, World : NWU + rotation offset { - const math::Quaterniond worldFrameOrientation(0, 0, IGN_PI/4); + const math::Quaterniond worldFrameOrientation(0, 0, GZ_PI/4); const sensors::WorldFrameEnumType worldRelativeTo = sensors::WorldFrameEnumType::NWU; - const math::Quaterniond expectedSensorOrientation(0, 0, -IGN_PI/4); + const math::Quaterniond expectedSensorOrientation(0, 0, -GZ_PI/4); sensorNWU->SetWorldFrameOrientation(worldFrameOrientation, worldRelativeTo); @@ -667,7 +667,7 @@ TEST(ImuSensor_TEST, NamedFrameOrientationReference) const math::Quaterniond worldFrameOrientation(0, 0, 0); const sensors::WorldFrameEnumType worldRelativeTo = sensors::WorldFrameEnumType::ENU; - const math::Quaterniond expectedSensorOrientation(0, 0, -IGN_PI/2); + const math::Quaterniond expectedSensorOrientation(0, 0, -GZ_PI/2); sensorNWU->SetWorldFrameOrientation(worldFrameOrientation, worldRelativeTo); @@ -682,7 +682,7 @@ TEST(ImuSensor_TEST, NamedFrameOrientationReference) const math::Quaterniond worldFrameOrientation(0, 0, 0); const sensors::WorldFrameEnumType worldRelativeTo = sensors::WorldFrameEnumType::NED; - const math::Quaterniond expectedSensorOrientation(IGN_PI, 0, 0); + const math::Quaterniond expectedSensorOrientation(GZ_PI, 0, 0); sensorNWU->SetWorldFrameOrientation(worldFrameOrientation, worldRelativeTo); @@ -714,10 +714,10 @@ TEST(ImuSensor_TEST, NamedFrameOrientationReference) // Case C.2 : Localization ref: NED, World : NED + rotation offset { - const math::Quaterniond worldFrameOrientation(0, 0, IGN_PI/4); + const math::Quaterniond worldFrameOrientation(0, 0, GZ_PI/4); const sensors::WorldFrameEnumType worldRelativeTo = sensors::WorldFrameEnumType::NED; - const math::Quaterniond expectedSensorOrientation(0, 0, -IGN_PI/4); + const math::Quaterniond expectedSensorOrientation(0, 0, -GZ_PI/4); sensorNED->SetWorldFrameOrientation(worldFrameOrientation, worldRelativeTo); @@ -732,7 +732,7 @@ TEST(ImuSensor_TEST, NamedFrameOrientationReference) const math::Quaterniond worldFrameOrientation(0, 0, 0); const sensors::WorldFrameEnumType worldRelativeTo = sensors::WorldFrameEnumType::NWU; - const math::Quaterniond expectedSensorOrientation(-IGN_PI, 0, 0); + const math::Quaterniond expectedSensorOrientation(-GZ_PI, 0, 0); sensorNED->SetWorldFrameOrientation(worldFrameOrientation, worldRelativeTo); @@ -747,7 +747,7 @@ TEST(ImuSensor_TEST, NamedFrameOrientationReference) const math::Quaterniond worldFrameOrientation(0, 0, 0); const sensors::WorldFrameEnumType worldRelativeTo = sensors::WorldFrameEnumType::ENU; - const math::Quaterniond expectedSensorOrientation(-IGN_PI, 0, IGN_PI/2); + const math::Quaterniond expectedSensorOrientation(-GZ_PI, 0, GZ_PI/2); sensorNED->SetWorldFrameOrientation(worldFrameOrientation, worldRelativeTo); diff --git a/src/Lidar.cc b/src/Lidar.cc index c237b5b1..33f851c1 100644 --- a/src/Lidar.cc +++ b/src/Lidar.cc @@ -220,7 +220,7 @@ void Lidar::ApplyNoise() ////////////////////////////////////////////////// bool Lidar::PublishLidarScan(const std::chrono::steady_clock::duration &_now) { - IGN_PROFILE("Lidar::PublishLidarScan"); + GZ_PROFILE("Lidar::PublishLidarScan"); if (!this->laserBuffer) return false; diff --git a/src/LogicalCameraSensor.cc b/src/LogicalCameraSensor.cc index bed044c1..f12f6b93 100644 --- a/src/LogicalCameraSensor.cc +++ b/src/LogicalCameraSensor.cc @@ -133,7 +133,7 @@ void LogicalCameraSensor::SetModelPoses( bool LogicalCameraSensor::Update( const std::chrono::steady_clock::duration &_now) { - IGN_PROFILE("LogicalCameraSensor::Update"); + GZ_PROFILE("LogicalCameraSensor::Update"); if (!this->dataPtr->initialized) { gzerr << "Not initialized, update ignored.\n"; diff --git a/src/MagnetometerSensor.cc b/src/MagnetometerSensor.cc index 2f1e5a92..80e2b1f7 100644 --- a/src/MagnetometerSensor.cc +++ b/src/MagnetometerSensor.cc @@ -152,7 +152,7 @@ bool MagnetometerSensor::Load(sdf::ElementPtr _sdf) bool MagnetometerSensor::Update( const std::chrono::steady_clock::duration &_now) { - IGN_PROFILE("MagnetometerSensor::Update"); + GZ_PROFILE("MagnetometerSensor::Update"); if (!this->dataPtr->initialized) { gzerr << "Not initialized, update ignored.\n"; diff --git a/src/Manager.cc b/src/Manager.cc index b528bdb3..b83a0003 100644 --- a/src/Manager.cc +++ b/src/Manager.cc @@ -75,7 +75,7 @@ bool Manager::Remove(const gz::sensors::SensorId _id) void Manager::RunOnce( const std::chrono::steady_clock::duration &_time, bool _force) { - IGN_PROFILE("SensorManager::RunOnce"); + GZ_PROFILE("SensorManager::RunOnce"); for (auto &s : this->dataPtr->sensors) { s.second->Update(_time, _force); diff --git a/src/NavSatSensor.cc b/src/NavSatSensor.cc index 511b6ba0..160f1448 100644 --- a/src/NavSatSensor.cc +++ b/src/NavSatSensor.cc @@ -149,7 +149,7 @@ bool NavSatSensor::Load(sdf::ElementPtr _sdf) ////////////////////////////////////////////////// bool NavSatSensor::Update(const std::chrono::steady_clock::duration &_now) { - IGN_PROFILE("NavSatSensor::Update"); + GZ_PROFILE("NavSatSensor::Update"); if (!this->dataPtr->loaded) { gzerr << "Not loaded, update ignored.\n"; @@ -164,8 +164,8 @@ bool NavSatSensor::Update(const std::chrono::steady_clock::duration &_now) auto iter = this->dataPtr->noises.find(NAVSAT_HORIZONTAL_POSITION_NOISE); if (iter != this->dataPtr->noises.end()) { - this->SetLatitude(IGN_DTOR(iter->second->Apply(this->Latitude().Degree()))); - this->SetLongitude(IGN_DTOR(iter->second->Apply( + this->SetLatitude(GZ_DTOR(iter->second->Apply(this->Latitude().Degree()))); + this->SetLongitude(GZ_DTOR(iter->second->Apply( this->Longitude().Degree()))); } iter = this->dataPtr->noises.find(NAVSAT_VERTICAL_POSITION_NOISE); diff --git a/src/Noise.cc b/src/Noise.cc index afccdf00..a9403ee4 100644 --- a/src/Noise.cc +++ b/src/Noise.cc @@ -68,7 +68,7 @@ NoisePtr NoiseFactory::NewNoiseModel(const sdf::Noise &_sdf, else noise.reset(new GaussianNoiseModel()); - IGN_ASSERT(noise->Type() == NoiseType::GAUSSIAN, + GZ_ASSERT(noise->Type() == NoiseType::GAUSSIAN, "Noise type should be 'gaussian'"); } else if (noiseType == sdf::NoiseType::NONE) @@ -77,7 +77,7 @@ NoisePtr NoiseFactory::NewNoiseModel(const sdf::Noise &_sdf, // if 'custom', the type will be set once the user calls the // SetCustomNoiseCallback function. noise.reset(new Noise(NoiseType::NONE)); - IGN_ASSERT(noise->Type() == NoiseType::NONE, + GZ_ASSERT(noise->Type() == NoiseType::NONE, "Noise type should be 'none'"); } else @@ -94,8 +94,8 @@ NoisePtr NoiseFactory::NewNoiseModel(const sdf::Noise &_sdf, NoisePtr NoiseFactory::NewNoiseModel(sdf::ElementPtr _sdf, const std::string &_sensorType) { - IGN_ASSERT(_sdf != nullptr, "noise sdf is null"); - IGN_ASSERT(_sdf->GetName() == "noise", "Not a noise SDF element"); + GZ_ASSERT(_sdf != nullptr, "noise sdf is null"); + GZ_ASSERT(_sdf->GetName() == "noise", "Not a noise SDF element"); sdf::Noise noiseDom; noiseDom.Load(_sdf); diff --git a/src/RenderingSensor.cc b/src/RenderingSensor.cc index a52194a0..8366e66f 100644 --- a/src/RenderingSensor.cc +++ b/src/RenderingSensor.cc @@ -100,7 +100,7 @@ bool RenderingSensor::ManualSceneUpdate() const ///////////////////////////////////////////////// void RenderingSensor::Render() { - IGN_PROFILE("RenderingSensor::Render"); + GZ_PROFILE("RenderingSensor::Render"); // Skip scene update. The user indicated that they will do this manually. // Performance is improved when a global scene update occurs only once per // frame, which can be acheived using a manual scene update. diff --git a/src/RgbdCameraSensor.cc b/src/RgbdCameraSensor.cc index 6b758e0d..0cccda8b 100644 --- a/src/RgbdCameraSensor.cc +++ b/src/RgbdCameraSensor.cc @@ -348,7 +348,7 @@ bool RgbdCameraSensor::CreateCameras() math::Angle angle = cameraSdf->HorizontalFov(); // todo(anyone) verify that rgb pixels align with d for angles >90 degrees. - if (angle < 0.01 || angle > IGN_PI * 2) + if (angle < 0.01 || angle > GZ_PI * 2) { gzerr << "Invalid horizontal field of view [" << angle << "]\n"; @@ -445,7 +445,7 @@ void RgbdCameraSensorPrivate::OnNewRgbPointCloud(const float *_scan, ////////////////////////////////////////////////// bool RgbdCameraSensor::Update(const std::chrono::steady_clock::duration &_now) { - IGN_PROFILE("RgbdCameraSensor::Update"); + GZ_PROFILE("RgbdCameraSensor::Update"); if (!this->dataPtr->initialized) { gzerr << "Not initialized, update ignored.\n"; @@ -508,7 +508,7 @@ bool RgbdCameraSensor::Update(const std::chrono::steady_clock::duration &_now) // publish { this->AddSequence(msg.mutable_header(), "depthImage"); - IGN_PROFILE("RgbdCameraSensor::Update Publish depth image"); + GZ_PROFILE("RgbdCameraSensor::Update Publish depth image"); this->dataPtr->depthPub.Publish(msg); } } @@ -549,7 +549,7 @@ bool RgbdCameraSensor::Update(const std::chrono::steady_clock::duration &_now) } { - IGN_PROFILE("RgbdCameraSensor::Update Fill Point Cloud"); + GZ_PROFILE("RgbdCameraSensor::Update Fill Point Cloud"); // fill point cloud msg and image data this->dataPtr->pointsUtil.FillMsg(this->dataPtr->pointMsg, this->dataPtr->pointCloudBuffer, true, @@ -560,7 +560,7 @@ bool RgbdCameraSensor::Update(const std::chrono::steady_clock::duration &_now) // publish { this->AddSequence(this->dataPtr->pointMsg.mutable_header(), "pointMsg"); - IGN_PROFILE("RgbdCameraSensor::Update Publish point cloud"); + GZ_PROFILE("RgbdCameraSensor::Update Publish point cloud"); this->dataPtr->pointPub.Publish(this->dataPtr->pointMsg); } } @@ -570,7 +570,7 @@ bool RgbdCameraSensor::Update(const std::chrono::steady_clock::duration &_now) { if (!filledImgData) { - IGN_PROFILE("RgbdCameraSensor::Update Fill RGB Image"); + GZ_PROFILE("RgbdCameraSensor::Update Fill RGB Image"); // extract image data from point cloud data this->dataPtr->pointsUtil.RGBFromPointCloud( this->dataPtr->image.Data(), @@ -596,7 +596,7 @@ bool RgbdCameraSensor::Update(const std::chrono::steady_clock::duration &_now) // publish the image message { this->AddSequence(msg.mutable_header(), "rgbdImage"); - IGN_PROFILE("RgbdCameraSensor::Update Publish RGB image"); + GZ_PROFILE("RgbdCameraSensor::Update Publish RGB image"); this->dataPtr->imagePub.Publish(msg); } } diff --git a/src/SegmentationCameraSensor.cc b/src/SegmentationCameraSensor.cc index 276d388a..d74343cc 100644 --- a/src/SegmentationCameraSensor.cc +++ b/src/SegmentationCameraSensor.cc @@ -344,7 +344,7 @@ bool SegmentationCameraSensor::CreateCamera() auto height = sdfCamera->ImageHeight(); math::Angle angle = sdfCamera->HorizontalFov(); - if (angle < 0.01 || angle > IGN_PI*2) + if (angle < 0.01 || angle > GZ_PI*2) { gzerr << "Invalid horizontal field of view [" << angle << "]\n"; return false; @@ -428,7 +428,7 @@ void SegmentationCameraSensor::OnNewSegmentationFrame(const uint8_t * _data, bool SegmentationCameraSensor::Update( const std::chrono::steady_clock::duration &_now) { - IGN_PROFILE("SegmentationCameraSensor::Update"); + GZ_PROFILE("SegmentationCameraSensor::Update"); if (!this->dataPtr->initialized) { gzerr << "Not initialized, update ignored.\n"; diff --git a/src/Sensor.cc b/src/Sensor.cc index 480e3b3b..cfd97fdc 100644 --- a/src/Sensor.cc +++ b/src/Sensor.cc @@ -439,7 +439,7 @@ void Sensor::SetUpdateRate(const double _hz) bool Sensor::Update(const std::chrono::steady_clock::duration &_now, const bool _force) { - IGN_PROFILE("Sensor::Update"); + GZ_PROFILE("Sensor::Update"); bool result = false; // Check if it's time to update diff --git a/src/SensorTypes.cc b/src/SensorTypes.cc index fa4d4943..5e9df4ca 100644 --- a/src/SensorTypes.cc +++ b/src/SensorTypes.cc @@ -21,7 +21,7 @@ using namespace gz; using namespace sensors; // Initialize enum iterator, and string converter -IGN_ENUM(sensorNoiseIface, sensors::SensorNoiseType, +GZ_ENUM(sensorNoiseIface, sensors::SensorNoiseType, sensors::SENSOR_NOISE_TYPE_BEGIN, sensors::SENSOR_NOISE_TYPE_END, "NO_NOISE", diff --git a/src/ThermalCameraSensor.cc b/src/ThermalCameraSensor.cc index 155f2ed0..398ebfc2 100644 --- a/src/ThermalCameraSensor.cc +++ b/src/ThermalCameraSensor.cc @@ -326,7 +326,7 @@ bool ThermalCameraSensor::CreateCamera() } math::Angle angle = cameraSdf->HorizontalFov(); - if (angle < 0.01 || angle > IGN_PI*2) + if (angle < 0.01 || angle > GZ_PI*2) { gzerr << "Invalid horizontal field of view [" << angle << "]\n"; @@ -409,7 +409,7 @@ void ThermalCameraSensor::SetScene(gz::rendering::ScenePtr _scene) bool ThermalCameraSensor::Update( const std::chrono::steady_clock::duration &_now) { - IGN_PROFILE("ThermalCameraSensor::Update"); + GZ_PROFILE("ThermalCameraSensor::Update"); if (!this->dataPtr->initialized) { gzerr << "Not initialized, update ignored.\n"; diff --git a/src/Util.cc b/src/Util.cc index f24b6846..f7fc0a3b 100644 --- a/src/Util.cc +++ b/src/Util.cc @@ -47,11 +47,22 @@ std::string gz::sensors::customType(sdf::ElementPtr _sdf) return std::string(); } - if (!_sdf->HasAttribute("ignition:type")) + if (!_sdf->HasAttribute("gz:type")) { - gzerr << "Custom sensor missing `ignition:type` attribute." << std::endl; - return std::string(); + // 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(); + } } - return _sdf->Get("ignition:type"); + return _sdf->Get("gz:type"); } diff --git a/src/Util_TEST.cc b/src/Util_TEST.cc index 38700fd4..d33d1019 100644 --- a/src/Util_TEST.cc +++ b/src/Util_TEST.cc @@ -82,7 +82,7 @@ TEST_F(Util_TEST, customType) { auto sensor = link->SensorByIndex(2); ASSERT_NE(nullptr, sensor); - EXPECT_EQ("missing_ignition_type", sensor->Name()); + EXPECT_EQ("missing_gz_type", sensor->Name()); EXPECT_TRUE(customType(*sensor).empty()); EXPECT_TRUE(customType(sensor->Element()).empty()); } diff --git a/src/WideAngleCameraSensor.cc b/src/WideAngleCameraSensor.cc index c5c4c45d..11913174 100644 --- a/src/WideAngleCameraSensor.cc +++ b/src/WideAngleCameraSensor.cc @@ -395,7 +395,7 @@ void WideAngleCameraSensor::SetScene(gz::rendering::ScenePtr _scene) bool WideAngleCameraSensor::Update( const std::chrono::steady_clock::duration &_now) { - IGN_PROFILE("WideAngleCameraSensor::Update"); + GZ_PROFILE("WideAngleCameraSensor::Update"); if (!this->dataPtr->initialized) { gzerr << "Not initialized, update ignored.\n"; @@ -468,7 +468,7 @@ bool WideAngleCameraSensor::Update( // create message gz::msgs::Image msg; { - IGN_PROFILE("WideAngleCameraSensor::Update Message"); + GZ_PROFILE("WideAngleCameraSensor::Update Message"); msg.set_width(width); msg.set_height(height); msg.set_step(width * rendering::PixelUtil::BytesPerPixel( @@ -486,7 +486,7 @@ bool WideAngleCameraSensor::Update( // publish the image message { this->AddSequence(msg.mutable_header()); - IGN_PROFILE("WideAngleCameraSensor::Update Publish"); + GZ_PROFILE("WideAngleCameraSensor::Update Publish"); this->dataPtr->pub.Publish(msg); // publish the camera info message diff --git a/test/integration/force_torque.cc b/test/integration/force_torque.cc index 57aa4c20..b8b811ee 100644 --- a/test/integration/force_torque.cc +++ b/test/integration/force_torque.cc @@ -231,9 +231,9 @@ TEST_P(ForceTorqueSensorTest, SensorReadings) // Set rotation of child const math::Quaterniond rotChildInSensor{ - math::Vector3d{IGN_PI_4, IGN_PI_2, 0}}; + math::Vector3d{GZ_PI_4, GZ_PI_2, 0}}; const math::Quaterniond rotParentInSensor{ - math::Vector3d{0, IGN_PI_4, IGN_PI_4}}; + math::Vector3d{0, GZ_PI_4, GZ_PI_4}}; sensor->SetRotationChildInSensor(rotChildInSensor); EXPECT_EQ(rotChildInSensor, sensor->RotationChildInSensor()); diff --git a/test/integration/gpu_lidar_sensor.cc b/test/integration/gpu_lidar_sensor.cc index 0d28d427..aff4deb2 100644 --- a/test/integration/gpu_lidar_sensor.cc +++ b/test/integration/gpu_lidar_sensor.cc @@ -293,8 +293,8 @@ void GpuLidarSensorTest::DetectBox(const std::string &_renderEngine) const double updateRate = 30; const int horzSamples = 320; const double horzResolution = 1; - const double horzMinAngle = -IGN_PI/2.0; - const double horzMaxAngle = IGN_PI/2.0; + const double horzMinAngle = -GZ_PI/2.0; + const double horzMaxAngle = GZ_PI/2.0; const double vertResolution = 1; const int vertSamples = 1; const double vertMinAngle = 0; @@ -439,8 +439,8 @@ void GpuLidarSensorTest::TestThreeBoxes(const std::string &_renderEngine) const double updateRate = 30; const int horzSamples = 320; const double horzResolution = 1; - const double horzMinAngle = -IGN_PI/2.0; - const double horzMaxAngle = IGN_PI/2.0; + const double horzMinAngle = -GZ_PI/2.0; + const double horzMaxAngle = GZ_PI/2.0; const double vertResolution = 1; const int vertSamples = 1; const double vertMinAngle = 0; @@ -461,7 +461,7 @@ void GpuLidarSensorTest::TestThreeBoxes(const std::string &_renderEngine) // Create a second sensor SDF rotated gz::math::Pose3d testPose2(gz::math::Vector3d(0, 0, 0.1), - gz::math::Quaterniond(IGN_PI/2.0, 0, 0)); + gz::math::Quaterniond(GZ_PI/2.0, 0, 0)); sdf::ElementPtr lidarSdf2 = GpuLidarToSdf(name2, testPose2, updateRate, topic2, horzSamples, horzResolution, horzMinAngle, horzMaxAngle, vertSamples, vertResolution, vertMinAngle, vertMaxAngle, @@ -588,12 +588,12 @@ void GpuLidarSensorTest::VerticalLidar(const std::string &_renderEngine) const double updateRate = 30; const unsigned int horzSamples = 640; const double horzResolution = 1; - const double horzMinAngle = -IGN_PI/2.0; - const double horzMaxAngle = IGN_PI/2.0; + const double horzMinAngle = -GZ_PI/2.0; + const double horzMaxAngle = GZ_PI/2.0; const double vertResolution = 1; const unsigned int vertSamples = 4; - const double vertMinAngle = -IGN_PI/4.0; - const double vertMaxAngle = IGN_PI/4.0; + const double vertMinAngle = -GZ_PI/4.0; + const double vertMaxAngle = GZ_PI/4.0; const double rangeResolution = 0.01; const double rangeMin = 0.08; const double rangeMax = 10.0; @@ -711,8 +711,8 @@ void GpuLidarSensorTest::ManualUpdate(const std::string &_renderEngine) const double updateRate = 30; const int horzSamples = 320; const double horzResolution = 1; - const double horzMinAngle = -IGN_PI/2.0; - const double horzMaxAngle = IGN_PI/2.0; + const double horzMinAngle = -GZ_PI/2.0; + const double horzMaxAngle = GZ_PI/2.0; const double vertResolution = 1; const int vertSamples = 1; const double vertMinAngle = 0; diff --git a/test/integration/navsat.cc b/test/integration/navsat.cc index 67291da0..7b1b7923 100644 --- a/test/integration/navsat.cc +++ b/test/integration/navsat.cc @@ -220,13 +220,13 @@ TEST_F(NavSatSensorTest, SensorReadings) EXPECT_DOUBLE_EQ(0.0, sensorNoise->Velocity().Z()); // set state and verify readings - math::Angle lat{IGN_DTOR(20)}; + math::Angle lat{GZ_DTOR(20)}; sensor->SetLatitude(lat); sensorNoise->SetLatitude(lat); EXPECT_EQ(lat, sensor->Latitude()); EXPECT_EQ(lat, sensorNoise->Latitude()); - math::Angle lon{IGN_DTOR(-20)}; + math::Angle lon{GZ_DTOR(-20)}; sensor->SetLongitude(lon); sensorNoise->SetLongitude(lon); EXPECT_EQ(lon, sensor->Longitude()); @@ -238,8 +238,8 @@ TEST_F(NavSatSensorTest, SensorReadings) EXPECT_DOUBLE_EQ(altitude, sensor->Altitude()); EXPECT_DOUBLE_EQ(altitude, sensorNoise->Altitude()); - lat += IGN_DTOR(20); - lon += IGN_DTOR(20); + lat += GZ_DTOR(20); + lon += GZ_DTOR(20); altitude += 100; sensor->SetPosition(lat, lon, altitude); sensorNoise->SetPosition(lat, lon, altitude); diff --git a/test/sdf/custom_sensors.sdf b/test/sdf/custom_sensors.sdf index 0ed0c731..bc4fa469 100644 --- a/test/sdf/custom_sensors.sdf +++ b/test/sdf/custom_sensors.sdf @@ -3,13 +3,13 @@ - + - + - + diff --git a/tutorials/custom_sensors.md b/tutorials/custom_sensors.md index b52610c2..d3dcec20 100644 --- a/tutorials/custom_sensors.md +++ b/tutorials/custom_sensors.md @@ -57,7 +57,7 @@ type. Seismometer? Breathalyzer? Just adapt the logic to your needs. Custom sensors follow these rules to be loaded from SDFormat: * Use `type="custom"` inside the `` tag -* Add an extra `ignition:type="odometer"` attribute, where `odometer` +* Add an extra `gz:type="odometer"` attribute, where `odometer` is a string that uniquely identifies the sensor type. * Optionally, add an `` element with configuration specific to that sensor. @@ -65,7 +65,7 @@ Custom sensors follow these rules to be loaded from SDFormat: With that in mind, here's what the sensor tag would look like: ```xml - + 1 30 odom diff --git a/tutorials/segmentation_camera.md b/tutorials/segmentation_camera.md index 98135345..53105d98 100644 --- a/tutorials/segmentation_camera.md +++ b/tutorials/segmentation_camera.md @@ -173,7 +173,7 @@ You can also attach this plugin to the model's `` tag: ``` -If you're including a model from a place like [ignition fuel](https://app.gazebosim.org/dashboard), you can add the label plugin as a child for the `` tag: +If you're including a model from a place like [Gazebo Fuel](https://app.gazebosim.org/dashboard), you can add the label plugin as a child for the `` tag: ```xml