diff --git a/src/systems/buoyancy_engine/BuoyancyEngine.hh b/src/systems/buoyancy_engine/BuoyancyEngine.hh index 422f5a703a..d7a92b2996 100644 --- a/src/systems/buoyancy_engine/BuoyancyEngine.hh +++ b/src/systems/buoyancy_engine/BuoyancyEngine.hh @@ -74,16 +74,19 @@ namespace systems /// gz sim buoyancy_engine.sdf /// ``` /// Enter the following in a separate terminal: - /// ``` - /// gz topic -t /model/buoyant_box/buoyancy_engine/ -m gz.msgs.Double \ - /// -p "data: 0.003" - /// ``` + /** ``` + gz topic -t /model/buoyant_box/buoyancy_engine/ -m gz.msgs.Double \ + -p "data: 0.003" + ``` + **/ /// to see the box float up. - /// ``` - /// gz topic -t /model/buoyant_box/buoyancy_engine/ -m gz.msgs.Double \ - /// -p "data: 0.001" - /// ``` + /** ``` + gz topic -t /model/buoyant_box/buoyancy_engine/ -m gz.msgs.Double \ + -p "data: 0.001" + ``` + **/ /// to see the box go down. + /// /// To see the current volume enter: /// ``` /// gz topic -t /model/buoyant_box/buoyancy_engine/current_volume -e diff --git a/src/systems/odometry_publisher/OdometryPublisher.hh b/src/systems/odometry_publisher/OdometryPublisher.hh index f7b462da7c..cab9bd6d14 100644 --- a/src/systems/odometry_publisher/OdometryPublisher.hh +++ b/src/systems/odometry_publisher/OdometryPublisher.hh @@ -36,44 +36,44 @@ namespace systems /// order to periodically publish 2D or 3D odometry data in the form of /// gz::msgs::Odometry messages. /// - /// # System Parameters + /// ## System Parameters /// - /// ``: Name of the world-fixed coordinate frame for the + /// - ``: Name of the world-fixed coordinate frame for the // odometry message. This element is optional, and the default value /// is `{name_of_model}/odom`. /// - /// ``: Name of the coordinate frame rigidly attached + /// - ``: Name of the coordinate frame rigidly attached /// to the mobile robot base. This element is optional, and the default /// value is `{name_of_model}/base_footprint`. /// - /// ``: Odometry publication frequency. This + /// - ``: Odometry publication frequency. This /// element is optional, and the default value is 50Hz. /// - /// ``: Custom topic on which this system will publish odometry + /// - ``: Custom topic on which this system will publish odometry /// messages. This element is optional, and the default value is /// `/model/{name_of_model}/odometry`. /// - /// ``: Custom topic on which this system will publish - /// odometry with covariance messages. This element is optional, and the - /// default value is `/model/{name_of_model}/odometry_with_covariance`. + /// - ``: Custom topic on which this system will + /// publish odometry with covariance messages. This element is optional, and + /// the default value is `/model/{name_of_model}/odometry_with_covariance`. /// - /// ``: Custom topic on which this system will publish the + /// - ``: Custom topic on which this system will publish the /// transform from `odom_frame` to `robot_base_frame`. This element is /// optional, and the default value is `/model/{name_of_model}/pose`. /// - /// ``: Number of dimensions to represent odometry. Only 2 and 3 + /// - ``: Number of dimensions to represent odometry. Only 2 and 3 /// dimensional spaces are supported. This element is optional, and the /// default value is 2. /// - /// ``: Position offset relative to the body fixed frame, the + /// - ``: Position offset relative to the body fixed frame, the /// default value is 0 0 0. This offset will be added to the odometry /// message. /// - /// ``: Rotation offset relative to the body fixed frame, the + /// - ``: Rotation offset relative to the body fixed frame, the /// default value is 0 0 0. This offset will be added to the odometry - /// message. + /// message. /// - /// ``: Standard deviation of the Gaussian noise to be added + /// - ``: Standard deviation of the Gaussian noise to be added /// to pose and twist messages. This element is optional, and the default /// value is 0. class OdometryPublisher diff --git a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.hh b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.hh index 664c109412..348cff0acf 100644 --- a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.hh +++ b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.hh @@ -37,54 +37,52 @@ namespace systems /// /// It requires that contact sensor and depth camera be placed in at least /// one link on the model on which this plugin is attached. - /// TODO: + /// + /// \todo(anyone) /// Currently, the contacts returned from the physics engine (which tends to /// be sparse) and the normal forces separately computed from the depth /// camera (which is dense, resolution adjustable) are disjoint. It is /// left as future work to combine the two sets of data. /// - /// Parameters: + /// ## System Parameters /// - /// Set this to true so the plugin works from the start and - /// doesn't need to be enabled. This element is optional, and the - /// default value is true. + /// - ``: Set this to true so the plugin works from the start and + /// doesn't need to be enabled. This element is optional, and the + /// default value is true. /// - /// Namespace for transport topics/services. If there are more - /// than one optical tactile plugins, their namespaces should - /// be different. - /// This element is optional, and the default value is - /// "optical_tactile_sensor". - /// //enable : Service used to enable and disable the - /// plugin. - /// //normal_forces : Topic where a message is - /// published each time the - /// normal forces are computed + /// - ``: Namespace for transport topics/services. If there are + /// more than one optical tactile plugins, their namespaces should + /// be different. This element is optional, and the default value is + /// "optical_tactile_sensor". + /// - `//enable`: Service used to enable and disable the plugin. + /// - `//normal_forces`: Topic where a message is + /// published each time the normal forces are computed /// - /// Number n of pixels to skip when visualizing - /// the forces. One vector representing a normal - /// force is computed for every nth pixel. This - /// element must be positive and it is optional. - /// The default value is 30. + /// - ``: Number n of pixels to skip when + /// visualizing the forces. One vector representing a normal + /// force is computed for every nth pixel. This + /// element must be positive and it is optional. + /// The default value is 30. /// - /// Length in meters of the forces visualized if - /// is set to true. This parameter is - /// optional, and the default value is 0.01. + /// - ``: Length in meters of the forces visualized if + /// is set to true. This parameter is + /// optional, and the default value is 0.01. /// - /// Extended sensing distance in meters. The sensor will - /// output data coming from its collision geometry plus - /// this distance. This element is optional, and the - /// default value is 0.001. + /// - ``: Extended sensing distance in meters. The sensor + /// will output data coming from its collision geometry plus + /// this distance. This element is optional, and the + /// default value is 0.001. /// - /// Whether to visualize the sensor or not. This element - /// is optional, and the default value is false. + /// - ``: Whether to visualize the sensor or not. This + /// element is optional, and the default value is false. /// - /// Whether to visualize the contacts from the contact - /// sensor based on physics. This element is optional, - /// and the default value is false. + /// - ``: Whether to visualize the contacts from the + /// contact sensor based on physics. This element is optional, + /// and the default value is false. /// - /// Whether to visualize normal forces computed from the - /// depth camera. This element is optional, and the - /// default value is false. + /// - ``: Whether to visualize normal forces computed from + /// the depth camera. This element is optional, and the + /// default value is false. class OpticalTactilePlugin : public System, diff --git a/src/systems/particle_emitter/ParticleEmitter.hh b/src/systems/particle_emitter/ParticleEmitter.hh index 848fa21a61..f6086bc2bb 100644 --- a/src/systems/particle_emitter/ParticleEmitter.hh +++ b/src/systems/particle_emitter/ParticleEmitter.hh @@ -32,10 +32,10 @@ namespace systems class ParticleEmitterPrivate; /// \brief A system for running and managing particle emitters. A particle - /// emitter is defined using the SDF element. + /// emitter is defined using the `` SDF element. /// /// This system will create a transport subscriber for each - /// using the child name. If a is not + /// `` using the child `` name. If a `` is not /// specified, the following topic naming scheme will be used: /// `/model/{model_name}/link/{link_name}/particle_emitter/{emitter_name}/cmd` class ParticleEmitter diff --git a/src/systems/performer_detector/PerformerDetector.hh b/src/systems/performer_detector/PerformerDetector.hh index bbdb9e3ddf..cd0c7f6f50 100644 --- a/src/systems/performer_detector/PerformerDetector.hh +++ b/src/systems/performer_detector/PerformerDetector.hh @@ -45,8 +45,9 @@ namespace systems /// PerformerDetector's region, which is also represented by an /// gz::math::AxisAlignedBox. When a performer is detected, the system /// publishes a gz.msgs.Pose message with the pose of the detected - /// performer with respect to the model containing the PerformerDetector. The - /// name and id fields of the Pose message will be set to the name and the + /// performer with respect to the model containing the PerformerDetector. + /// + /// The name and id fields of the Pose message will be set to the name and the /// entity of the detected performer respectively. The header of the Pose /// message contains the time stamp of detection. The `data` field of the /// header will contain the key "frame_id" with a value set to the name of @@ -62,19 +63,22 @@ namespace systems /// The system does not assume that levels are enabled, but it does require /// performers to be specified. /// - /// ## System parameters + /// ## System Parameters /// - /// ``: Custom topic to be used for publishing when a performer is + /// - ``: Custom topic to be used for publishing when a performer is /// detected. If not set, the default topic with the following pattern would /// be used "/model//performer_detector/status". The topic type /// is gz.msgs.Pose - /// ``: Detection region. Currently, only the `` geometry is + /// + /// - ``: Detection region. Currently, only the `` geometry is /// supported. The position of the geometry is derived from the pose of the /// containing model. - /// ``: Additional pose offset relative to the parent model's pose. + /// + /// - ``: Additional pose offset relative to the parent model's pose. /// This pose is added to the parent model pose when computing the /// detection region. Only the position component of the `` is used. - /// ``: Zero or more key-value pairs that will be + /// + /// - ``: Zero or more key-value pairs that will be /// included in the header of the detection messages. A `` /// element should have child `` and `` elements whose /// contents are interpreted as strings. Keys value pairs are stored in a diff --git a/src/systems/physics/Physics.hh b/src/systems/physics/Physics.hh index d7944668e2..cec62d341c 100644 --- a/src/systems/physics/Physics.hh +++ b/src/systems/physics/Physics.hh @@ -64,9 +64,15 @@ namespace systems /// \class Physics Physics.hh gz/sim/systems/Physics.hh /// \brief Base class for a System. - /// Includes optional parameter : . When set + /// + /// ## System Parameters + /// + /// - ``: Optional. When set /// to false, the name of colliding entities is not populated in - /// the contacts. Remains true by default. Usage : + /// the contacts. Remains true by default. + /// + /// ## Example + /// /// ``` /// : Name of python module to be loaded. The search path +/// ## System Parameters +/// * `` : Name of python module to be loaded. The search path /// includes `GZ_SIM_SYSTEM_PLUGIN_PATH` as well as /// `PYTHONPATH`. /// -/// The contents of the tag will be available in the configure method +/// The contents of the `` tag will be available in the configure method /// of the Python system // TODO(azeey) Add ParameterConfigure class GZ_SIM_PYTHON_SYSTEM_LOADER_SYSTEM_HIDDEN PythonSystemLoader final diff --git a/src/systems/rf_comms/RFComms.hh b/src/systems/rf_comms/RFComms.hh index 550ca70b12..16ccf0c0cd 100644 --- a/src/systems/rf_comms/RFComms.hh +++ b/src/systems/rf_comms/RFComms.hh @@ -38,31 +38,37 @@ namespace systems /// This communication model has been ported from: /// https://github.com/osrf/subt . /// + /// ## System Parameters + /// /// This system can be configured with the following SDF parameters: /// - /// * Optional parameters: - /// Element used to capture the range configuration based on a - /// log-normal distribution. This block can contain any of the - /// next parameters: - /// * : Hard limit on range (meters). No communication will - /// happen beyond this range. Default is 50. - /// * : Fading exponent used in the normal distribution. - /// Default is 2.5. - /// * : Path loss at the reference distance (1 meter) in dBm. - /// Default is 40. - /// * : Standard deviation of the normal distribution. - /// Default is 10. + /// Optional parameters: + /// + /// - ``: Element used to capture the range configuration based + /// on a log-normal distribution. This block can contain any of the + /// next parameters: + /// - ``: Hard limit on range (meters). No communication will + /// happen beyond this range. Default is 50. + /// - ``: Fading exponent used in the normal distribution. + /// Default is 2.5. + /// - ``: Path loss at the reference distance (1 meter) in dBm. + /// Default is 40. + /// - ``: Standard deviation of the normal distribution. + /// Default is 10. + /// + /// - ``: Element used to capture the radio configuration. + /// This block can contain any of the + /// next parameters: + /// - ``: Capacity of radio in bits-per-second. + /// Default is 54000000 (54 Mbps). + /// - ``: Transmitter power in dBm. Default is 27dBm (500mW). + /// - ``: Noise floor in dBm. Default is -90dBm. + /// - ``: Supported modulations: ["QPSK"]. Default is "QPSK". /// - /// Element used to capture the radio configuration. - /// This block can contain any of the - /// next parameters: - /// * : Capacity of radio in bits-per-second. - /// Default is 54000000 (54 Mbps). - /// * : Transmitter power in dBm. Default is 27dBm (500mW). - /// * : Noise floor in dBm. Default is -90dBm. - /// * : Supported modulations: ["QPSK"]. Default is "QPSK". + /// ## Example /// /// Here's an example: + /// ``` /// @@ -79,6 +85,7 @@ namespace systems /// QPSK /// /// + /// ``` class RFComms : public comms::ICommsModel { diff --git a/src/systems/sensors/Sensors.hh b/src/systems/sensors/Sensors.hh index caf533ce29..41a314e757 100644 --- a/src/systems/sensors/Sensors.hh +++ b/src/systems/sensors/Sensors.hh @@ -40,14 +40,14 @@ namespace systems /// /// ## System Parameters /// - /// - `` Name of the render engine, such as 'ogre' or 'ogre2'. - /// - `` Color used for the scene's background. This + /// - ``: Name of the render engine, such as "ogre" or "ogre2". + /// - ``: Color used for the scene's background. This /// will override the background color specified in a world's SDF /// element. This background color is used by sensors, not the GUI. - /// - `` Color used for the scene's ambient light. This + /// - ``: Color used for the scene's ambient light. This /// will override the ambient value specified in a world's SDF /// element. This ambient light is used by sensors, not the GUI. - /// - `` Disable sensors if the model's + /// - ``: Disable sensors if the model's /// battery plugin charge reaches zero. Sensors that are in nested /// models are also affected. /// diff --git a/src/systems/shader_param/ShaderParam.hh b/src/systems/shader_param/ShaderParam.hh index 6c6d4a4215..8197d08015 100644 --- a/src/systems/shader_param/ShaderParam.hh +++ b/src/systems/shader_param/ShaderParam.hh @@ -35,42 +35,42 @@ namespace systems /// \brief A plugin for setting shaders to a visual and its params /// - /// Plugin parameters: + /// ## System Parameters /// - /// Shader to use - can be repeated to specify shader programs - /// written in different languages. - /// Attributes: - /// language - Shader language. Possible values: glsl, metal - /// Default to glsl if not specified - /// Path to vertex program - /// Path to fragment program - /// Shader parameter - can be repeated within plugin SDF element - /// Name of uniform variable bound to the shader - /// Type of shader, i.e. vertex, fragment - /// Variable type: float, int, float_array, int_array - /// Value to set the shader parameter to. The vallue string can - /// be an int, float, or a space delimited array of ints or - /// floats. It can also be 'TIME', in which case the value will - /// be bound to sim time. + /// - ``: Shader to use - can be repeated to specify shader programs + /// written in different languages. + /// - Attributes: + /// - `language`: Shader language. Possible values: glsl, metal + /// Default to glsl if not specified + /// - ``: Path to vertex program + /// - ``: Path to fragment program + /// - ``: Shader parameter - can be repeated within plugin SDF element + /// - ``: Name of uniform variable bound to the shader + /// - ``: Type of shader, i.e. vertex, fragment + /// - ``: Variable type: float, int, float_array, int_array + /// - ``: Value to set the shader parameter to. The vallue string can + /// be an int, float, or a space delimited array of ints or + /// floats. It can also be "TIME", in which case the value will + /// be bound to sim time. /// - /// Example usage: + /// ## Example /// - /// \verbatim - /// - /// - /// materials/my_vs.glsl - /// materials/my_fs.glsl - /// - /// - /// - /// ambient - /// fragment - /// float_array - /// 1.0 0.0 0.0 1.0 - /// - /// - /// \endverbatim + /// ``` + /// + /// + /// materials/my_vs.glsl + /// materials/my_fs.glsl + /// + /// + /// + /// ambient + /// fragment + /// float_array + /// 1.0 0.0 0.0 1.0 + /// + /// + /// ``` class ShaderParam : public System, public ISystemConfigure, diff --git a/src/systems/thruster/Thruster.hh b/src/systems/thruster/Thruster.hh index 5c9cdab562..708fddf883 100644 --- a/src/systems/thruster/Thruster.hh +++ b/src/systems/thruster/Thruster.hh @@ -46,64 +46,75 @@ namespace systems /// `/model/{ns}/joint/{joint_name}/force`. /// /// ## System Parameters - /// - - The namespace in which the robot exists. The plugin will + /// + /// - ``: The namespace in which the robot exists. The plugin will /// listen on the topic `/model/{namespace}/joint/{joint_name}/cmd_thrust`or /// `/model/{namespace}/joint/{joint_name}/cmd_vel` depending on the mode of /// operation. If {topic} is set then the plugin will listen on /// {namespace}/{topic} /// [Optional] - /// - - The topic for receiving thrust commands. [Optional] - /// - - This is the joint in the model which corresponds to the + /// - ``: The topic for receiving thrust commands. [Optional] + /// - ``: This is the joint in the model which corresponds to the /// propeller. [Required] - /// - - If set to true will make the thruster + /// - ``: If set to true will make the thruster /// plugin accept commands in angular velocity in radians per seconds in /// terms of newtons. [Optional, Boolean, defaults to false] - /// - - The fluid density of the liquid in which the thruster + /// - ``: The fluid density of the liquid in which the thruster /// is operating in. [Optional, kg/m^3, defaults to 1000 kg/m^3] - /// - - The diameter of the propeller in meters. + /// - ``: The diameter of the propeller in meters. /// [Optional, m, defaults to 0.02m] - /// - - This is the coefficient which relates the angular - /// velocity to thrust. A positive coefficient corresponds to a clockwise - /// propeller, which is a propeller that spins clockwise under positive - /// thrust when viewed along the parent link from stern (-x) to bow (+x). - /// [Optional, no units, defaults to 1.0] - /// - /// omega = sqrt(thrust / - /// (fluid_density * thrust_coefficient * propeller_diameter ^ 4)) - /// - /// Where omega is the propeller's angular velocity in rad/s. - /// - - If true, use joint velocity commands to rotate the + /// - ``: This is the coefficient which relates the + /// angular velocity to thrust. A positive coefficient corresponds to a + /// clockwise propeller, which is a propeller that spins clockwise under + /// positive thrust when viewed along the parent link from stern (-x) to + /// bow (+x). [Optional, no units, defaults to 1.0] + /// ``` + /// omega = sqrt(thrust / + /// (fluid_density * thrust_coefficient * propeller_diameter ^ 4)) + /// ``` + /// where omega is the propeller's angular velocity in rad/s. + /// - ``: If true, use joint velocity commands to rotate the /// propeller. If false, use a PID controller to apply wrenches directly to /// the propeller link instead. [Optional, defaults to false]. - /// - - Proportional gain for joint PID controller. [Optional, - /// no units, defaults to 0.1] - /// - - Integral gain for joint PID controller. [Optional, - /// no units, defaults to 0.0] - /// - - Derivative gain for joint PID controller. [Optional, - /// no units, defaults to 0.0] - /// - - Maximum input thrust or angular velocity command. - /// [Optional, defaults to 1000N or 1000rad/s] - /// - - Minimum input thrust or angular velocity command. - /// [Optional, defaults to -1000N or -1000rad/s] - /// - - Deadband of the thruster. Absolute value below which the - /// thruster won't spin nor generate thrust. This value can - /// be changed at runtime using a topic. The topic is either - /// `/model/{ns}/joint/{jointName}/enable_deadband` or - /// `{ns}/{topic}/enable_deadband` depending on other params - /// - - Relative speed reduction between the water + /// - ``: Proportional gain for joint PID controller. [Optional, + /// no units, defaults to 0.1] + /// - ``: Integral gain for joint PID controller. [Optional, + /// no units, defaults to 0.0] + /// - ``: Derivative gain for joint PID controller. [Optional, + /// no units, defaults to 0.0] + /// - ``: Maximum input thrust or angular velocity command. + /// [Optional, defaults to 1000N or 1000rad/s] + /// - ``: Minimum input thrust or angular velocity command. + /// [Optional, defaults to -1000N or -1000rad/s] + /// - ``: Deadband of the thruster. Absolute value below which the + /// thruster won't spin nor generate thrust. This value can + /// be changed at runtime using a topic. The topic is either + /// `/model/{ns}/joint/{jointName}/enable_deadband` or + /// `{ns}/{topic}/enable_deadband` depending on other params + /// - ``: Relative speed reduction between the water /// at the propeller (Va) vs behind the vessel. /// [Optional, defults to 0.2] - /// See Thor I Fossen's "Guidance and Control of ocean vehicles" p. 95: - /// Va = (1 - wake_fraction) * advance_speed - /// - - Constant given by the open water propeller diagram. Used - /// in the calculation of the thrust coefficient (Kt). - /// [Optional, defults to 1] - /// - - Constant given by the open water propeller diagram. Used - /// in the calculation of the thrust coefficient (Kt). - /// [Optional, defults to 0] - /// See Thor I Fossen's "Guidance and Control of ocean vehicles" p. 95: - /// Kt = alpha_1 * alpha_2 * (Va/(propeller_revolution * propeller_diameter)) + /// + /// See Thor I Fossen's "Guidance and Control of ocean vehicles" p. 95: + /// ``` + /// Va = (1 - wake_fraction) * advance_speed + /// ``` + /// + /// - ``: Constant given by the open water propeller diagram. Used + /// in the calculation of the thrust coefficient (Kt). + /// [Optional, defults to 1] + /// - ``: Constant given by the open water propeller diagram. Used + /// in the calculation of the thrust coefficient (Kt). + /// [Optional, defults to 0] + /// + /// See Thor I Fossen's "Guidance and Control of ocean vehicles" p. 95: + /// ``` + /// Kt = alpha_1 * alpha_2 * + /// (Va / (propeller_revolution * propeller_diameter)) + /// ``` + /// /// ## Example + /// /// An example configuration is installed with Gazebo. The example /// uses the LiftDrag plugin to apply steering controls. It also uses the /// thruster plugin to propell the craft and the buoyancy plugin for buoyant @@ -112,15 +123,17 @@ namespace systems /// gz sim auv_controls.sdf /// ``` /// To control the rudder of the craft run the following: - /// ``` - /// gz topic -t /model/tethys/joint/vertical_fins_joint/0/cmd_pos - /// -m gz.msgs.Double -p 'data: -0.17' - /// ``` + /** ``` + gz topic -t /model/tethys/joint/vertical_fins_joint/0/cmd_pos \ + -m gz.msgs.Double -p 'data: -0.17' + ``` + **/ /// To apply a thrust you may run the following command: - /// ``` - /// gz topic -t /model/tethys/joint/propeller_joint/cmd_thrust - /// -m gz.msgs.Double -p 'data: -31' - /// ``` + /** ``` + gz topic -t /model/tethys/joint/propeller_joint/cmd_thrust \ + -m gz.msgs.Double -p 'data: -31' + ``` + **/ /// The vehicle should move in a circle. class Thruster: public gz::sim::System, diff --git a/src/systems/touch_plugin/TouchPlugin.hh b/src/systems/touch_plugin/TouchPlugin.hh index 0912671ca0..da1be1e841 100644 --- a/src/systems/touch_plugin/TouchPlugin.hh +++ b/src/systems/touch_plugin/TouchPlugin.hh @@ -42,7 +42,7 @@ namespace systems /// The plugin requires that a contact sensors is placed in at least one /// link on the model on which this plugin is attached. /// - /// Parameters: + /// ## System Parameters /// /// - `` Name, or substring of a name, that identifies the target /// collision entity/entities. @@ -50,15 +50,15 @@ namespace systems /// entities, so it can possibly match more than one collision. /// For example, using the name of a model will match all of its /// collisions (scoped name - /// /model_name/link_name/collision_name). + /// `/model_name/link_name/collision_name`). /// /// - `