Skip to content

Commit

Permalink
Fix doxygen errors
Browse files Browse the repository at this point in the history
Signed-off-by: Addisu Z. Taddese <[email protected]>
  • Loading branch information
azeey committed Jul 24, 2023
1 parent 8e16623 commit ccec18d
Show file tree
Hide file tree
Showing 12 changed files with 40 additions and 41 deletions.
3 changes: 2 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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/)
Expand Down
2 changes: 1 addition & 1 deletion include/gz/sensors/AirPressureSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
2 changes: 1 addition & 1 deletion include/gz/sensors/AltimeterSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
10 changes: 5 additions & 5 deletions include/gz/sensors/DepthCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
2 changes: 1 addition & 1 deletion include/gz/sensors/ForceTorqueSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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);

Expand Down
4 changes: 2 additions & 2 deletions include/gz/sensors/ImuSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ namespace gz
/// \brief Reference frames enum
enum class GZ_SENSORS_VISIBLE WorldFrameEnumType
{
/// \brief NONE : To be used only when <localization>
/// \brief NONE : To be used only when `<localization>`
/// reference orientation tag is empty.
NONE = 0,

Expand Down Expand Up @@ -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);

Expand Down
12 changes: 6 additions & 6 deletions include/gz/sensors/Lidar.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -173,22 +173,22 @@ 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) <your accessor loop>
/// problem by using SetActive(false) `<your accessor loop>`
/// 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<double> &_ranges) const;

/// \brief Get detected retro (intensity) value for a ray.
/// Warning: If you are accessing all the ray data in a loop
/// 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) <your accessor loop>
/// problem by using SetActive(false) `<your accessor loop>`
/// SetActive(true).
/// \param[in] _index Index of specific ray
/// \return Intensity value of ray
Expand All @@ -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) <your accessor loop>
/// problem by using SetActive(false) `<your accessor loop>`
/// SetActive(true).
/// \param[in] _index Index of specific ray
/// \return Fiducial value of ray
Expand Down Expand Up @@ -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.
Expand Down
24 changes: 12 additions & 12 deletions include/gz/sensors/Manager.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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 <plugin> tag of the sdf::Element. The manager will
/// be in the `<plugin>` 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
Expand Down Expand Up @@ -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 <sensor> tag may have multiple <plugin> tags. A SensorId will be
/// returned for each plugin that is described in SDF.
/// If there are no <plugin> tags then one of the plugins shipped with
/// this library will be loaded. For example, a <sensor> tag with
/// <camera> but no <plugin> will load a CameraSensor from
/// A `<sensor>` tag may have multiple `<plugin>` tags. A SensorId will
/// be returned for each plugin that is described in SDF.
/// If there are no `<plugin>` tags then one of the plugins shipped with
/// this library will be loaded. For example, a `<sensor>` tag with
/// `<camera>` but no `<plugin>` will load a CameraSensor from
/// gz-sensors-camera.
/// \sa Sensor()
/// \param[in] _sdf pointer to the sdf element
Expand All @@ -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 <sensor> tag may have multiple <plugin> tags. A SensorId will be
/// returned for each plugin that is described in SDF.
/// If there are no <plugin> tags then one of the plugins shipped with
/// this library will be loaded. For example, a <sensor> tag with
/// <camera> but no <plugin> will load a CameraSensor from
/// A `<sensor>` tag may have multiple `<plugin>` tags. A SensorId will
/// be returned for each plugin that is described in SDF.
/// If there are no `<plugin>` tags then one of the plugins shipped with
/// this library will be loaded. For example, a `<sensor>` tag with
/// `<camera>` but no `<plugin>` will load a CameraSensor from
/// gz-sensors-camera.
/// \sa Sensor()
/// \param[in] _sdf SDF sensor DOM object
Expand All @@ -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);

Expand Down
12 changes: 6 additions & 6 deletions include/gz/sensors/Sensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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 <sensor> 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 `<sensor>` tag and is responsible for making sure
/// sensors update at the right time.
class GZ_SENSORS_VISIBLE Sensor
{
/// \brief constructor
Expand All @@ -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 <sensor> or <plugin> inside of <sensor>
/// \param[in] _sdf SDF `<sensor>` or `<plugin>` inside of `<sensor>`
/// \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 <sensor> or <plugin> inside of <sensor>
/// \param[in] _sdf SDF `<sensor>` or `<plugin>` inside of `<sensor>`
/// \return true if loading was successful
public: virtual bool Load(sdf::ElementPtr _sdf);

Expand Down Expand Up @@ -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);

Expand Down
4 changes: 1 addition & 3 deletions include/gz/sensors/SensorTypes.hh
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ namespace gz
/// \brief Shared pointer to Noise
typedef std::shared_ptr<Noise> NoisePtr;

/// \def GaussianNoisePtr
/// \def GaussianNoiseModelPtr
/// \brief Shared pointer to Noise
typedef std::shared_ptr<GaussianNoiseModel> GaussianNoiseModelPtr;

Expand Down Expand Up @@ -214,7 +214,6 @@ namespace gz
/// use this.
SENSOR_NOISE_TYPE_END
};
/// \}


/// \def SensorDistortionType
Expand All @@ -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.
Expand Down
4 changes: 2 additions & 2 deletions include/gz/sensors/ThermalCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down Expand Up @@ -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.
Expand Down
2 changes: 1 addition & 1 deletion include/gz/sensors/WideAngleCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down

0 comments on commit ccec18d

Please sign in to comment.