Skip to content

Commit fdbda58

Browse files
authored
Standardize Doxygen parameter formatting for systems O-Z (#2212)
* standardize system parameter doxygen for plugins O-Z * 80 chars * Update TrackedVehicle.hh * fix lint * gcc warning about multi-line comment Signed-off-by: Mabel Zhang <[email protected]>
1 parent ac26d9c commit fdbda58

File tree

19 files changed

+449
-382
lines changed

19 files changed

+449
-382
lines changed

src/systems/buoyancy_engine/BuoyancyEngine.hh

+11-8
Original file line numberDiff line numberDiff line change
@@ -74,16 +74,19 @@ namespace systems
7474
/// gz sim buoyancy_engine.sdf
7575
/// ```
7676
/// Enter the following in a separate terminal:
77-
/// ```
78-
/// gz topic -t /model/buoyant_box/buoyancy_engine/ -m gz.msgs.Double \
79-
/// -p "data: 0.003"
80-
/// ```
77+
/** ```
78+
gz topic -t /model/buoyant_box/buoyancy_engine/ -m gz.msgs.Double \
79+
-p "data: 0.003"
80+
```
81+
**/
8182
/// to see the box float up.
82-
/// ```
83-
/// gz topic -t /model/buoyant_box/buoyancy_engine/ -m gz.msgs.Double \
84-
/// -p "data: 0.001"
85-
/// ```
83+
/** ```
84+
gz topic -t /model/buoyant_box/buoyancy_engine/ -m gz.msgs.Double \
85+
-p "data: 0.001"
86+
```
87+
**/
8688
/// to see the box go down.
89+
///
8790
/// To see the current volume enter:
8891
/// ```
8992
/// gz topic -t /model/buoyant_box/buoyancy_engine/current_volume -e

src/systems/odometry_publisher/OdometryPublisher.hh

+14-14
Original file line numberDiff line numberDiff line change
@@ -36,44 +36,44 @@ namespace systems
3636
/// order to periodically publish 2D or 3D odometry data in the form of
3737
/// gz::msgs::Odometry messages.
3838
///
39-
/// # System Parameters
39+
/// ## System Parameters
4040
///
41-
/// `<odom_frame>`: Name of the world-fixed coordinate frame for the
41+
/// - `<odom_frame>`: Name of the world-fixed coordinate frame for the
4242
// odometry message. This element is optional, and the default value
4343
/// is `{name_of_model}/odom`.
4444
///
45-
/// `<robot_base_frame>`: Name of the coordinate frame rigidly attached
45+
/// - `<robot_base_frame>`: Name of the coordinate frame rigidly attached
4646
/// to the mobile robot base. This element is optional, and the default
4747
/// value is `{name_of_model}/base_footprint`.
4848
///
49-
/// `<odom_publish_frequency>`: Odometry publication frequency. This
49+
/// - `<odom_publish_frequency>`: Odometry publication frequency. This
5050
/// element is optional, and the default value is 50Hz.
5151
///
52-
/// `<odom_topic>`: Custom topic on which this system will publish odometry
52+
/// - `<odom_topic>`: Custom topic on which this system will publish odometry
5353
/// messages. This element is optional, and the default value is
5454
/// `/model/{name_of_model}/odometry`.
5555
///
56-
/// `<odom_covariance_topic>`: Custom topic on which this system will publish
57-
/// odometry with covariance messages. This element is optional, and the
58-
/// default value is `/model/{name_of_model}/odometry_with_covariance`.
56+
/// - `<odom_covariance_topic>`: Custom topic on which this system will
57+
/// publish odometry with covariance messages. This element is optional, and
58+
/// the default value is `/model/{name_of_model}/odometry_with_covariance`.
5959
///
60-
/// `<tf_topic>`: Custom topic on which this system will publish the
60+
/// - `<tf_topic>`: Custom topic on which this system will publish the
6161
/// transform from `odom_frame` to `robot_base_frame`. This element is
6262
/// optional, and the default value is `/model/{name_of_model}/pose`.
6363
///
64-
/// `<dimensions>`: Number of dimensions to represent odometry. Only 2 and 3
64+
/// - `<dimensions>`: Number of dimensions to represent odometry. Only 2 and 3
6565
/// dimensional spaces are supported. This element is optional, and the
6666
/// default value is 2.
6767
///
68-
/// `<xyz_offset>`: Position offset relative to the body fixed frame, the
68+
/// - `<xyz_offset>`: Position offset relative to the body fixed frame, the
6969
/// default value is 0 0 0. This offset will be added to the odometry
7070
/// message.
7171
///
72-
/// `<rpy_offset>`: Rotation offset relative to the body fixed frame, the
72+
/// - `<rpy_offset>`: Rotation offset relative to the body fixed frame, the
7373
/// default value is 0 0 0. This offset will be added to the odometry
74-
/// message.
74+
/// message.
7575
///
76-
/// `<gaussian_noise>`: Standard deviation of the Gaussian noise to be added
76+
/// - `<gaussian_noise>`: Standard deviation of the Gaussian noise to be added
7777
/// to pose and twist messages. This element is optional, and the default
7878
/// value is 0.
7979
class OdometryPublisher

src/systems/optical_tactile_plugin/OpticalTactilePlugin.hh

+33-35
Original file line numberDiff line numberDiff line change
@@ -37,54 +37,52 @@ namespace systems
3737
///
3838
/// It requires that contact sensor and depth camera be placed in at least
3939
/// one link on the model on which this plugin is attached.
40-
/// TODO:
40+
///
41+
/// \todo(anyone)
4142
/// Currently, the contacts returned from the physics engine (which tends to
4243
/// be sparse) and the normal forces separately computed from the depth
4344
/// camera (which is dense, resolution adjustable) are disjoint. It is
4445
/// left as future work to combine the two sets of data.
4546
///
46-
/// Parameters:
47+
/// ## System Parameters
4748
///
48-
/// <enabled> Set this to true so the plugin works from the start and
49-
/// doesn't need to be enabled. This element is optional, and the
50-
/// default value is true.
49+
/// - `<enabled>`: Set this to true so the plugin works from the start and
50+
/// doesn't need to be enabled. This element is optional, and the
51+
/// default value is true.
5152
///
52-
/// <namespace> Namespace for transport topics/services. If there are more
53-
/// than one optical tactile plugins, their namespaces should
54-
/// be different.
55-
/// This element is optional, and the default value is
56-
/// "optical_tactile_sensor".
57-
/// /<namespace>/enable : Service used to enable and disable the
58-
/// plugin.
59-
/// /<namespace>/normal_forces : Topic where a message is
60-
/// published each time the
61-
/// normal forces are computed
53+
/// - `<namespace>`: Namespace for transport topics/services. If there are
54+
/// more than one optical tactile plugins, their namespaces should
55+
/// be different. This element is optional, and the default value is
56+
/// "optical_tactile_sensor".
57+
/// - `/<namespace>/enable`: Service used to enable and disable the plugin.
58+
/// - `/<namespace>/normal_forces`: Topic where a message is
59+
/// published each time the normal forces are computed
6260
///
63-
/// <visualization_resolution> Number n of pixels to skip when visualizing
64-
/// the forces. One vector representing a normal
65-
/// force is computed for every nth pixel. This
66-
/// element must be positive and it is optional.
67-
/// The default value is 30.
61+
/// - `<visualization_resolution>`: Number n of pixels to skip when
62+
/// visualizing the forces. One vector representing a normal
63+
/// force is computed for every nth pixel. This
64+
/// element must be positive and it is optional.
65+
/// The default value is 30.
6866
///
69-
/// <force_length> Length in meters of the forces visualized if
70-
/// <visualize_forces> is set to true. This parameter is
71-
/// optional, and the default value is 0.01.
67+
/// - `<force_length>`: Length in meters of the forces visualized if
68+
/// <visualize_forces> is set to true. This parameter is
69+
/// optional, and the default value is 0.01.
7270
///
73-
/// <extended_sensing> Extended sensing distance in meters. The sensor will
74-
/// output data coming from its collision geometry plus
75-
/// this distance. This element is optional, and the
76-
/// default value is 0.001.
71+
/// - `<extended_sensing>`: Extended sensing distance in meters. The sensor
72+
/// will output data coming from its collision geometry plus
73+
/// this distance. This element is optional, and the
74+
/// default value is 0.001.
7775
///
78-
/// <visualize_sensor> Whether to visualize the sensor or not. This element
79-
/// is optional, and the default value is false.
76+
/// - `<visualize_sensor>`: Whether to visualize the sensor or not. This
77+
/// element is optional, and the default value is false.
8078
///
81-
/// <visualize_contacts> Whether to visualize the contacts from the contact
82-
/// sensor based on physics. This element is optional,
83-
/// and the default value is false.
79+
/// - `<visualize_contacts>`: Whether to visualize the contacts from the
80+
/// contact sensor based on physics. This element is optional,
81+
/// and the default value is false.
8482
///
85-
/// <visualize_forces> Whether to visualize normal forces computed from the
86-
/// depth camera. This element is optional, and the
87-
/// default value is false.
83+
/// - `<visualize_forces>`: Whether to visualize normal forces computed from
84+
/// the depth camera. This element is optional, and the
85+
/// default value is false.
8886

8987
class OpticalTactilePlugin :
9088
public System,

src/systems/particle_emitter/ParticleEmitter.hh

+2-2
Original file line numberDiff line numberDiff line change
@@ -32,10 +32,10 @@ namespace systems
3232
class ParticleEmitterPrivate;
3333

3434
/// \brief A system for running and managing particle emitters. A particle
35-
/// emitter is defined using the <particle_emitter> SDF element.
35+
/// emitter is defined using the `<particle_emitter>` SDF element.
3636
///
3737
/// This system will create a transport subscriber for each
38-
/// <particle_emitter> using the child <topic> name. If a <topic> is not
38+
/// `<particle_emitter>` using the child `<topic>` name. If a `<topic>` is not
3939
/// specified, the following topic naming scheme will be used:
4040
/// `/model/{model_name}/link/{link_name}/particle_emitter/{emitter_name}/cmd`
4141
class ParticleEmitter

src/systems/performer_detector/PerformerDetector.hh

+11-7
Original file line numberDiff line numberDiff line change
@@ -45,8 +45,9 @@ namespace systems
4545
/// PerformerDetector's region, which is also represented by an
4646
/// gz::math::AxisAlignedBox. When a performer is detected, the system
4747
/// publishes a gz.msgs.Pose message with the pose of the detected
48-
/// performer with respect to the model containing the PerformerDetector. The
49-
/// name and id fields of the Pose message will be set to the name and the
48+
/// performer with respect to the model containing the PerformerDetector.
49+
///
50+
/// The name and id fields of the Pose message will be set to the name and the
5051
/// entity of the detected performer respectively. The header of the Pose
5152
/// message contains the time stamp of detection. The `data` field of the
5253
/// header will contain the key "frame_id" with a value set to the name of
@@ -62,19 +63,22 @@ namespace systems
6263
/// The system does not assume that levels are enabled, but it does require
6364
/// performers to be specified.
6465
///
65-
/// ## System parameters
66+
/// ## System Parameters
6667
///
67-
/// `<topic>`: Custom topic to be used for publishing when a performer is
68+
/// - `<topic>`: Custom topic to be used for publishing when a performer is
6869
/// detected. If not set, the default topic with the following pattern would
6970
/// be used "/model/<model_name>/performer_detector/status". The topic type
7071
/// is gz.msgs.Pose
71-
/// `<geometry>`: Detection region. Currently, only the `<box>` geometry is
72+
///
73+
/// - `<geometry>`: Detection region. Currently, only the `<box>` geometry is
7274
/// supported. The position of the geometry is derived from the pose of the
7375
/// containing model.
74-
/// `<pose>`: Additional pose offset relative to the parent model's pose.
76+
///
77+
/// - `<pose>`: Additional pose offset relative to the parent model's pose.
7578
/// This pose is added to the parent model pose when computing the
7679
/// detection region. Only the position component of the `<pose>` is used.
77-
/// `<header_data>`: Zero or more key-value pairs that will be
80+
///
81+
/// - `<header_data>`: Zero or more key-value pairs that will be
7882
/// included in the header of the detection messages. A `<header_data>`
7983
/// element should have child `<key>` and `<value>` elements whose
8084
/// contents are interpreted as strings. Keys value pairs are stored in a

src/systems/physics/Physics.hh

+8-2
Original file line numberDiff line numberDiff line change
@@ -64,9 +64,15 @@ namespace systems
6464

6565
/// \class Physics Physics.hh gz/sim/systems/Physics.hh
6666
/// \brief Base class for a System.
67-
/// Includes optional parameter : <include_entity_names>. When set
67+
///
68+
/// ## System Parameters
69+
///
70+
/// - `<include_entity_names>`: Optional. When set
6871
/// to false, the name of colliding entities is not populated in
69-
/// the contacts. Remains true by default. Usage :
72+
/// the contacts. Remains true by default.
73+
///
74+
/// ## Example
75+
///
7076
/// ```
7177
/// <plugin
7278
/// filename="gz-sim-physics-system"

src/systems/python_system_loader/PythonSystemLoader.hh

+4-4
Original file line numberDiff line numberDiff line change
@@ -55,14 +55,14 @@ namespace systems
5555
/// check if the corresponding method is implemented in the Python system and
5656
/// skip it if it's not found.
5757
///
58-
/// See examples/scripts/python_api/systems/test_system.py for an example
58+
/// See `examples/scripts/python_api/systems/test_system.py` for an example
5959
///
60-
/// ## Parameters
61-
/// * <module_name> : Name of python module to be loaded. The search path
60+
/// ## System Parameters
61+
/// * `<module_name>` : Name of python module to be loaded. The search path
6262
/// includes `GZ_SIM_SYSTEM_PLUGIN_PATH` as well as
6363
/// `PYTHONPATH`.
6464
///
65-
/// The contents of the <plugin> tag will be available in the configure method
65+
/// The contents of the `<plugin>` tag will be available in the configure method
6666
/// of the Python system
6767
// TODO(azeey) Add ParameterConfigure
6868
class GZ_SIM_PYTHON_SYSTEM_LOADER_SYSTEM_HIDDEN PythonSystemLoader final

src/systems/rf_comms/RFComms.hh

+27-20
Original file line numberDiff line numberDiff line change
@@ -38,31 +38,37 @@ namespace systems
3838
/// This communication model has been ported from:
3939
/// https://github.com/osrf/subt .
4040
///
41+
/// ## System Parameters
42+
///
4143
/// This system can be configured with the following SDF parameters:
4244
///
43-
/// * Optional parameters:
44-
/// <range_config> Element used to capture the range configuration based on a
45-
/// log-normal distribution. This block can contain any of the
46-
/// next parameters:
47-
/// * <max_range>: Hard limit on range (meters). No communication will
48-
/// happen beyond this range. Default is 50.
49-
/// * <fading_exponent>: Fading exponent used in the normal distribution.
50-
/// Default is 2.5.
51-
/// * <l0>: Path loss at the reference distance (1 meter) in dBm.
52-
/// Default is 40.
53-
/// * <sigma>: Standard deviation of the normal distribution.
54-
/// Default is 10.
45+
/// Optional parameters:
46+
///
47+
/// - `<range_config>`: Element used to capture the range configuration based
48+
/// on a log-normal distribution. This block can contain any of the
49+
/// next parameters:
50+
/// - `<max_range>`: Hard limit on range (meters). No communication will
51+
/// happen beyond this range. Default is 50.
52+
/// - `<fading_exponent>`: Fading exponent used in the normal distribution.
53+
/// Default is 2.5.
54+
/// - `<l0>`: Path loss at the reference distance (1 meter) in dBm.
55+
/// Default is 40.
56+
/// - `<sigma>`: Standard deviation of the normal distribution.
57+
/// Default is 10.
58+
///
59+
/// - `<radio_config>`: Element used to capture the radio configuration.
60+
/// This block can contain any of the
61+
/// next parameters:
62+
/// - `<capacity>`: Capacity of radio in bits-per-second.
63+
/// Default is 54000000 (54 Mbps).
64+
/// - `<tx_power>`: Transmitter power in dBm. Default is 27dBm (500mW).
65+
/// - `<noise_floor>`: Noise floor in dBm. Default is -90dBm.
66+
/// - `<modulation>`: Supported modulations: ["QPSK"]. Default is "QPSK".
5567
///
56-
/// <radio_config> Element used to capture the radio configuration.
57-
/// This block can contain any of the
58-
/// next parameters:
59-
/// * <capacity>: Capacity of radio in bits-per-second.
60-
/// Default is 54000000 (54 Mbps).
61-
/// * <tx_power>: Transmitter power in dBm. Default is 27dBm (500mW).
62-
/// * <noise_floor>: Noise floor in dBm. Default is -90dBm.
63-
/// * <modulation>: Supported modulations: ["QPSK"]. Default is "QPSK".
68+
/// ## Example
6469
///
6570
/// Here's an example:
71+
/// ```
6672
/// <plugin
6773
/// filename="gz-sim-rf-comms-system"
6874
/// name="gz::sim::systems::RFComms">
@@ -79,6 +85,7 @@ namespace systems
7985
/// <modulation>QPSK</modulation>
8086
/// </radio_config>
8187
/// </plugin>
88+
/// ```
8289
class RFComms
8390
: public comms::ICommsModel
8491
{

src/systems/sensors/Sensors.hh

+4-4
Original file line numberDiff line numberDiff line change
@@ -40,14 +40,14 @@ namespace systems
4040
///
4141
/// ## System Parameters
4242
///
43-
/// - `<render_engine>` Name of the render engine, such as 'ogre' or 'ogre2'.
44-
/// - `<background_color>` Color used for the scene's background. This
43+
/// - `<render_engine>`: Name of the render engine, such as "ogre" or "ogre2".
44+
/// - `<background_color>`: Color used for the scene's background. This
4545
/// will override the background color specified in a world's SDF <scene>
4646
/// element. This background color is used by sensors, not the GUI.
47-
/// - `<ambient_light>` Color used for the scene's ambient light. This
47+
/// - `<ambient_light>`: Color used for the scene's ambient light. This
4848
/// will override the ambient value specified in a world's SDF <scene>
4949
/// element. This ambient light is used by sensors, not the GUI.
50-
/// - `<disable_on_drained_battery>` Disable sensors if the model's
50+
/// - `<disable_on_drained_battery>`: Disable sensors if the model's
5151
/// battery plugin charge reaches zero. Sensors that are in nested
5252
/// models are also affected.
5353
///

0 commit comments

Comments
 (0)