From ccec18dcee45103fede09a9ed598b49179819b77 Mon Sep 17 00:00:00 2001 From: "Addisu Z. Taddese" Date: Mon, 24 Jul 2023 16:48:19 -0500 Subject: [PATCH] Fix doxygen errors Signed-off-by: Addisu Z. Taddese --- CMakeLists.txt | 3 ++- include/gz/sensors/AirPressureSensor.hh | 2 +- include/gz/sensors/AltimeterSensor.hh | 2 +- include/gz/sensors/DepthCameraSensor.hh | 10 ++++----- include/gz/sensors/ForceTorqueSensor.hh | 2 +- include/gz/sensors/ImuSensor.hh | 4 ++-- include/gz/sensors/Lidar.hh | 12 +++++------ include/gz/sensors/Manager.hh | 24 ++++++++++----------- include/gz/sensors/Sensor.hh | 12 +++++------ include/gz/sensors/SensorTypes.hh | 4 +--- include/gz/sensors/ThermalCameraSensor.hh | 4 ++-- include/gz/sensors/WideAngleCameraSensor.hh | 2 +- 12 files changed, 40 insertions(+), 41 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 68cb8497..ef5b383f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -112,7 +112,8 @@ configure_file(${CMAKE_SOURCE_DIR}/tutorials.md.in ${CMAKE_BINARY_DIR}/tutorials gz_create_docs( API_MAINPAGE_MD "${CMAKE_BINARY_DIR}/api.md" - TUTORIALS_MAINPAGE_MD "${CMAKE_BINARY_DIR}/tutorials.md") + TUTORIALS_MAINPAGE_MD "${CMAKE_BINARY_DIR}/tutorials.md" + IMAGE_PATH_DIRS "${CMAKE_SOURCE_DIR}/tutorials/files") if(TARGET doc) file(COPY ${CMAKE_SOURCE_DIR}/tutorials/files/ DESTINATION ${CMAKE_BINARY_DIR}/doxygen/html/files/) diff --git a/include/gz/sensors/AirPressureSensor.hh b/include/gz/sensors/AirPressureSensor.hh index aa2e66c6..faf3dc6c 100644 --- a/include/gz/sensors/AirPressureSensor.hh +++ b/include/gz/sensors/AirPressureSensor.hh @@ -73,7 +73,7 @@ namespace gz const std::chrono::steady_clock::duration &_now) override; /// \brief Set the reference altitude. - /// \param[in] _ref Verical reference position in meters + /// \param[in] _reference Verical reference position in meters public: void SetReferenceAltitude(double _reference); /// \brief Get the vertical reference altitude. diff --git a/include/gz/sensors/AltimeterSensor.hh b/include/gz/sensors/AltimeterSensor.hh index f1abf2a1..619cf8b3 100644 --- a/include/gz/sensors/AltimeterSensor.hh +++ b/include/gz/sensors/AltimeterSensor.hh @@ -73,7 +73,7 @@ namespace gz const std::chrono::steady_clock::duration &_now) override; /// \brief Set the vertical reference position of the altimeter - /// \param[in] _ref Verical reference position in meters + /// \param[in] _reference Verical reference position in meters public: void SetVerticalReference(double _reference); /// \brief Get the vertical reference position of the altimeter diff --git a/include/gz/sensors/DepthCameraSensor.hh b/include/gz/sensors/DepthCameraSensor.hh index f2896353..660ab594 100644 --- a/include/gz/sensors/DepthCameraSensor.hh +++ b/include/gz/sensors/DepthCameraSensor.hh @@ -101,19 +101,19 @@ namespace gz /// \param[in] _format string with the format public: void OnNewDepthFrame(const float *_scan, unsigned int _width, unsigned int _height, - unsigned int /*_channels*/, - const std::string &/*_format*/); + unsigned int _channel, + const std::string &_format); /// \brief Point cloud data callback used to get the data from the sensor /// \param[in] _scan pointer to the data from the sensor /// \param[in] _width width of the point cloud image /// \param[in] _height height of the point cloud image - /// \param[in] _channel bytes used for the point cloud data + /// \param[in] _channels bytes used for the point cloud data /// \param[in] _format string with the format public: void OnNewRgbPointCloud(const float *_scan, unsigned int _width, unsigned int _height, - unsigned int /*_channels*/, - const std::string &/*_format*/); + unsigned int _channels, + const std::string &_format); /// \brief Set a callback to be called when image frame data is /// generated. diff --git a/include/gz/sensors/ForceTorqueSensor.hh b/include/gz/sensors/ForceTorqueSensor.hh index bf4babc7..c6cf1c85 100644 --- a/include/gz/sensors/ForceTorqueSensor.hh +++ b/include/gz/sensors/ForceTorqueSensor.hh @@ -100,7 +100,7 @@ namespace gz /// \brief Set the rotation of the joint parent relative to the sensor /// frame. - /// \param[in] _rotParentInSensorRotation of parent in sensor frame. + /// \param[in] _rotParentInSensor Rotation of parent in sensor frame. public: void SetRotationParentInSensor( const math::Quaterniond &_rotParentInSensor); diff --git a/include/gz/sensors/ImuSensor.hh b/include/gz/sensors/ImuSensor.hh index e827db4a..78bbd1bf 100644 --- a/include/gz/sensors/ImuSensor.hh +++ b/include/gz/sensors/ImuSensor.hh @@ -39,7 +39,7 @@ namespace gz /// \brief Reference frames enum enum class GZ_SENSORS_VISIBLE WorldFrameEnumType { - /// \brief NONE : To be used only when + /// \brief NONE : To be used only when `` /// reference orientation tag is empty. NONE = 0, @@ -125,7 +125,7 @@ namespace gz /// \brief Set the orientation reference, i.e. initial imu /// orientation. Imu orientation data generated will be relative to this /// reference frame. - /// \param[in] _orientation Reference orientation + /// \param[in] _orient Reference orientation public: void SetOrientationReference( const math::Quaterniond &_orient); diff --git a/include/gz/sensors/Lidar.hh b/include/gz/sensors/Lidar.hh index 988533e6..5a4edf46 100644 --- a/include/gz/sensors/Lidar.hh +++ b/include/gz/sensors/Lidar.hh @@ -86,7 +86,7 @@ namespace gz public: virtual bool Init() override; /// \brief Initialize values in the sensor - /// \return True on success + /// \param[in] _parent Name of parent public: void SetParent(const std::string &_parent) override; /// \brief Create Lidar sensor @@ -173,14 +173,14 @@ namespace gz /// it's possible that the Ray will update in the middle of /// your access loop. This means some data will come from one /// scan, and some from another scan. You can solve this - /// problem by using SetActive(false) + /// problem by using SetActive(false) `` /// SetActive(true). /// \param[in] _index Index of specific ray /// \return Returns RangeMax for no detection. public: double Range(const int _index) const; /// \brief Get all the ranges - /// \param[out] _range A vector that will contain all the range data + /// \param[out] _ranges A vector that will contain all the range data public: void Ranges(std::vector &_ranges) const; /// \brief Get detected retro (intensity) value for a ray. @@ -188,7 +188,7 @@ namespace gz /// it's possible that the Ray will update in the middle of /// your access loop. This means some data will come from one /// scan, and some from another scan. You can solve this - /// problem by using SetActive(false) + /// problem by using SetActive(false) `` /// SetActive(true). /// \param[in] _index Index of specific ray /// \return Intensity value of ray @@ -199,7 +199,7 @@ namespace gz /// it's possible that the Ray will update in the middle of /// your access loop. This means some data will come from one /// scan, and some from another scan. You can solve this - /// problem by using SetActive(false) + /// problem by using SetActive(false) `` /// SetActive(true). /// \param[in] _index Index of specific ray /// \return Fiducial value of ray @@ -256,7 +256,7 @@ namespace gz public: bool initialized = false; /// \brief Set a callback to be called when data is generated. - /// \param[in] _callback This callback will be called every time the + /// \param[in] _subscriber This callback will be called every time the /// sensor generates data. The Update function will be blocked while the /// callbacks are executed. /// \remark Do not block inside of the callback. diff --git a/include/gz/sensors/Manager.hh b/include/gz/sensors/Manager.hh index a0661076..97b9036e 100644 --- a/include/gz/sensors/Manager.hh +++ b/include/gz/sensors/Manager.hh @@ -47,7 +47,7 @@ namespace gz /// The primary interface through which to load a sensor is LoadSensor(). /// This takes an sdf element pointer that should be configured with /// everything the sensor will need. Custom sensors configuration must - /// be in the tag of the sdf::Element. The manager will + /// be in the `` tag of the sdf::Element. The manager will /// dynamically load the sensor library and update it. /// \remarks This class is not thread safe. class GZ_SENSORS_VISIBLE Manager @@ -96,11 +96,11 @@ namespace gz /// 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 + /// 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 @@ -119,11 +119,11 @@ namespace gz /// 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 + /// 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 @@ -149,7 +149,7 @@ namespace gz gz::sensors::SensorId _id); /// \brief Remove a sensor by ID - /// \param[in] _sensorId ID of the sensor to remove + /// \param[in] _id ID of the sensor to remove /// \return True if the sensor exists and removed. public: bool Remove(const gz::sensors::SensorId _id); diff --git a/include/gz/sensors/Sensor.hh b/include/gz/sensors/Sensor.hh index 146ebf61..f6a9e813 100644 --- a/include/gz/sensors/Sensor.hh +++ b/include/gz/sensors/Sensor.hh @@ -53,9 +53,9 @@ namespace gz /// \brief a base sensor class /// - /// This class is a base for all sensor classes. It parses some common - /// SDF elements in the tag and is responsible for making sure - /// sensors update at the right time. + /// This class is a base for all sensor classes. It parses some common + /// SDF elements in the `` tag and is responsible for making sure + /// sensors update at the right time. class GZ_SENSORS_VISIBLE Sensor { /// \brief constructor @@ -65,12 +65,12 @@ namespace gz public: virtual ~Sensor(); /// \brief Load the sensor based on data from an sdf::Sensor object. - /// \param[in] _sdf SDF or inside of + /// \param[in] _sdf SDF `` or `` inside of `` /// \return true if loading was successful public: virtual bool Load(const sdf::Sensor &_sdf); /// \brief Load the sensor with SDF parameters. - /// \param[in] _sdf SDF or inside of + /// \param[in] _sdf SDF `` or `` inside of `` /// \return true if loading was successful public: virtual bool Load(sdf::ElementPtr _sdf); @@ -131,7 +131,7 @@ namespace gz /// \brief Set the update rate of the sensor. An update rate of zero means /// that the sensor is updated every cycle. It's zero by default. - /// \detail Negative rates become zero. + /// \details Negative rates become zero. /// \param[in] _hz Update rate of sensor in Hertz. public: void SetUpdateRate(const double _hz); diff --git a/include/gz/sensors/SensorTypes.hh b/include/gz/sensors/SensorTypes.hh index 81607c9b..5e096c34 100644 --- a/include/gz/sensors/SensorTypes.hh +++ b/include/gz/sensors/SensorTypes.hh @@ -63,7 +63,7 @@ namespace gz /// \brief Shared pointer to Noise typedef std::shared_ptr NoisePtr; - /// \def GaussianNoisePtr + /// \def GaussianNoiseModelPtr /// \brief Shared pointer to Noise typedef std::shared_ptr GaussianNoiseModelPtr; @@ -214,7 +214,6 @@ namespace gz /// use this. SENSOR_NOISE_TYPE_END }; - /// \} /// \def SensorDistortionType @@ -239,7 +238,6 @@ namespace gz /// use this. SENSOR_DISTORTION_TYPE_END }; - /// \} /// \brief SensorCategory is used to categorize sensors. This is used to /// put sensors into different threads. diff --git a/include/gz/sensors/ThermalCameraSensor.hh b/include/gz/sensors/ThermalCameraSensor.hh index 0dfb6916..ebf8c1bc 100644 --- a/include/gz/sensors/ThermalCameraSensor.hh +++ b/include/gz/sensors/ThermalCameraSensor.hh @@ -97,7 +97,7 @@ namespace gz /// \param[in] _scan pointer to the data from the sensor /// \param[in] _width width of the thermal image /// \param[in] _height height of the thermal image - /// \param[in] _channel bytes used for the thermal data + /// \param[in] _channels bytes used for the thermal data /// \param[in] _format string with the format public: void OnNewThermalFrame(const uint16_t *_scan, unsigned int _width, unsigned int _height, @@ -149,7 +149,7 @@ namespace gz /// returned will be temperature in kelvin / resolution. /// Typical values are 0.01 (10mK), 0.1 (100mK), or 0.04 to simulate /// 14 bit format. - /// \param[in] resolution Temperature linear resolution + /// \param[in] _resolution Temperature linear resolution public: virtual void SetLinearResolution(float _resolution); // Documentation inherited. diff --git a/include/gz/sensors/WideAngleCameraSensor.hh b/include/gz/sensors/WideAngleCameraSensor.hh index 7089390d..9266e8d0 100644 --- a/include/gz/sensors/WideAngleCameraSensor.hh +++ b/include/gz/sensors/WideAngleCameraSensor.hh @@ -97,7 +97,7 @@ namespace gz /// \param[in] _data pointer to the data from the sensor /// \param[in] _width width of the image /// \param[in] _height height of the image - /// \param[in] _channel bytes used for the image data + /// \param[in] _channels bytes used for the image data /// \param[in] _format string with the format public: void OnNewWideAngleFrame(const unsigned char *_data, unsigned int _width, unsigned int _height,