diff --git a/examples/plugin/custom_sensor_system/CMakeLists.txt b/examples/plugin/custom_sensor_system/CMakeLists.txt index 66ceb25192..32bb92dac3 100644 --- a/examples/plugin/custom_sensor_system/CMakeLists.txt +++ b/examples/plugin/custom_sensor_system/CMakeLists.txt @@ -20,7 +20,7 @@ include(FetchContent) FetchContent_Declare( sensors_clone GIT_REPOSITORY https://github.com/gazebosim/gz-sensors - GIT_TAG main + GIT_TAG gz-sensors8 ) FetchContent_Populate(sensors_clone) add_subdirectory(${sensors_clone_SOURCE_DIR}/examples/custom_sensor ${sensors_clone_BINARY_DIR}) diff --git a/src/systems/ackermann_steering/AckermannSteering.hh b/src/systems/ackermann_steering/AckermannSteering.hh index f82e0cec20..3d829d8902 100644 --- a/src/systems/ackermann_steering/AckermannSteering.hh +++ b/src/systems/ackermann_steering/AckermannSteering.hh @@ -36,106 +36,106 @@ namespace systems /// \brief Ackermann steering controller which can be attached to a model /// with any number of left and right wheels. /// - /// # System Parameters + /// ## System Parameters /// - /// ``: Boolean used to only control the steering angle + /// - ``: Boolean used to only control the steering angle /// only. Calculates the angles of wheels from steering_limit, wheel_base, /// and wheel_separation. Uses gz::msg::Double on default topic name /// `/model/{name_of_model}/steer_angle`. Automatically set True when /// `` is True, uses defaults topic name "/actuators". /// - /// `` True to enable the use of actutor message + /// - `` True to enable the use of actutor message /// for steering angle command. Relies on `` for the /// index of the position actuator and defaults to topic "/actuators". /// - /// `` used with `` to set + /// - `` used with `` to set /// the index of the steering angle position actuator. /// - /// ``: Float used to control the steering angle P gain. + /// - ``: Float used to control the steering angle P gain. /// Only used for when in steering_only mode. /// - /// ``: Name of a joint that controls a left wheel. This + /// - ``: Name of a joint that controls a left wheel. This /// element can appear multiple times, and must appear at least once. /// - /// ``: Name of a joint that controls a right wheel. This + /// - ``: Name of a joint that controls a right wheel. This /// element can appear multiple times, and must appear at least once. /// - /// ``: Name of a joint that controls steering for - /// left wheel. This element must appear once. Vehicles that steer - /// rear wheels are not currently correctly supported. + /// - ``: Name of a joint that controls steering for + /// left wheel. This element must appear once. Vehicles that steer + /// rear wheels are not currently correctly supported. /// - /// ``: Name of a joint that controls steering for - /// right wheel. This element must appear once. + /// - ``: Name of a joint that controls steering for + /// right wheel. This element must appear once. /// - /// ``: Distance between wheels, in meters. This element + /// - ``: Distance between wheels, in meters. This element /// is optional, although it is recommended to be included with an /// appropriate value. The default value is 1.0m. /// - /// ``: Distance between wheel kingpins, in meters. This + /// - ``: Distance between wheel kingpins, in meters. This /// element is optional, although it is recommended to be included with an /// appropriate value. The default value is 0.8m. Generally a bit smaller /// than the wheel_separation. /// - /// ``: Distance between front and rear wheels, in meters. This + /// - ``: Distance between front and rear wheels, in meters. This /// element is optional, although it is recommended to be included with an /// appropriate value. The default value is 1.0m. /// - /// ``: Value to limit steering to. Can be calculated by + /// - ``: Value to limit steering to. Can be calculated by /// measuring the turning radius and wheel_base of the real vehicle. /// steering_limit = asin(wheel_base / turning_radius) /// The default value is 0.5 radians. /// - /// ``: Wheel radius in meters. This element is optional, + /// - ``: Wheel radius in meters. This element is optional, /// although it is recommended to be included with an appropriate value. The /// default value is 0.2m. /// - /// ``: Odometry publication frequency. This + /// - ``: Odometry publication frequency. This /// element is optional, and the default value is 50Hz. /// - /// ``: Minimum velocity [m/s], usually <= 0. - /// ``: Maximum velocity [m/s], usually >= 0. - /// ``: Minimum acceleration [m/s^2], usually <= 0. - /// ``: Maximum acceleration [m/s^2], usually >= 0. - /// ``: jerk [m/s^3], usually <= 0. - /// ``: jerk [m/s^3], usually >= 0. + /// - ``: Minimum velocity [m/s], usually <= 0. + /// - ``: Maximum velocity [m/s], usually >= 0. + /// - ``: Minimum acceleration [m/s^2], usually <= 0. + /// - ``: Maximum acceleration [m/s^2], usually >= 0. + /// - ``: jerk [m/s^3], usually <= 0. + /// - ``: jerk [m/s^3], usually >= 0. /// - /// ``: Custom topic that this system will subscribe to in order to + /// - ``: Custom topic that this system will subscribe to in order to /// receive command messages. This element is optional, and the /// default value is `/model/{name_of_model}/cmd_vel` or when steering_only /// is true `/model/{name_of_model}/steer_angle`. /// - /// ``: Custom sub_topic that this system will subscribe to in + /// - ``: Custom sub_topic that this system will subscribe to in /// order to receive command messages. This element is optional, and /// creates a topic `/model/{name_of_model}/{sub_topic}` /// - /// ``: Custom topic on which this system will publish odometry + /// - ``: Custom topic on which this system will publish odometry /// messages. This element if optional, and the default value is /// `/model/{name_of_model}/odometry`. /// - /// ``: Custom topic on which this system will publish the + /// - ``: Custom topic on which this system will publish the /// transform from `frame_id` to `child_frame_id`. This element is optional, /// and the default value is `/model/{name_of_model}/tf`. /// - /// ``: Custom `frame_id` field that this system will use as the + /// - ``: Custom `frame_id` field that this system will use as the /// origin of the odometry transform in both the `` /// `gz.msgs.Pose_V` message and the `` /// `gz.msgs.Odometry` message. This element if optional, and the /// default value is `{name_of_model}/odom`. /// - /// ``: Custom `child_frame_id` that this system will use as + /// - ``: Custom `child_frame_id` that this system will use as /// the target of the odometry transform in both the `` - /// `gz.msgs.Pose_V` message and the `` - /// `gz.msgs.Odometry` message. This element if optional, + /// gz.msgs.Pose_V message and the `` + /// gz.msgs.Odometry message. This element is optional, /// and the default value is `{name_of_model}/{name_of_link}`. /// /// A robot with rear drive and front steering would have one each /// of left_joint, right_joint, left_steering_joint and - /// right_steering_joint + /// right_steering_joint. /// /// References: - /// https://github.com/gazebosim/gz-sim/tree/main/src/systems/ackermann_steering - /// https://www.auto.tuwien.ac.at/bib/pdf_TR/TR0183.pdf - /// https://github.com/froohoo/ackermansteer/blob/master/ackermansteer/ + /// - https://github.com/gazebosim/gz-sim/tree/main/src/systems/ackermann_steering + /// - https://www.auto.tuwien.ac.at/bib/pdf_TR/TR0183.pdf + /// - https://github.com/froohoo/ackermansteer/blob/master/ackermansteer/ class AckermannSteering diff --git a/src/systems/acoustic_comms/AcousticComms.hh b/src/systems/acoustic_comms/AcousticComms.hh index 2845436cef..45e7db8845 100644 --- a/src/systems/acoustic_comms/AcousticComms.hh +++ b/src/systems/acoustic_comms/AcousticComms.hh @@ -76,6 +76,7 @@ namespace systems /// * : Seed value to be used for random sampling. /// /// Here's an example: + /// ``` /// @@ -93,6 +94,7 @@ namespace systems /// /// /// + /// ``` class AcousticComms: public gz::sim::comms::ICommsModel diff --git a/src/systems/battery_plugin/LinearBatteryPlugin.hh b/src/systems/battery_plugin/LinearBatteryPlugin.hh index f82afa7515..2f142d37e5 100644 --- a/src/systems/battery_plugin/LinearBatteryPlugin.hh +++ b/src/systems/battery_plugin/LinearBatteryPlugin.hh @@ -39,12 +39,13 @@ namespace systems /// \brief A plugin for simulating battery usage /// - /// This system processes the following sdf parameters: + /// ## System parameters + /// /// - `` name of the battery (required) /// - `` Initial voltage of the battery (required) /// - `` Voltage at full charge /// - `` Amount of voltage decrease when no - /// charge + /// charge /// - `` Initial charge of the battery (Ah) /// - `` Total charge that the battery can hold (Ah) /// - `` Internal resistance (Ohm) @@ -52,22 +53,22 @@ namespace systems /// - `` power load on battery (required) (Watts) /// - `` If true, the battery can be recharged /// - `` If true, the start/stop signals for recharging the - /// battery will also be available via topics. The - /// regular Gazebo services will still be available. + /// battery will also be available via topics. The + /// regular Gazebo services will still be available. /// - `` Hours taken to fully charge the battery. - /// (Required if `` is set to true) + /// (Required if `` is set to true) /// - `` True to change the battery behavior to fix some issues - /// described in https://github.com/gazebosim/gz-sim/issues/225. + /// described in https://github.com/gazebosim/gz-sim/issues/225. /// - `` Whether to start draining the battery right away. - /// False by default. + /// False by default. /// - `` A topic that is used to start battery - /// discharge. Any message on the specified topic will cause the battery to - /// start draining. This element can be specified multiple times if - /// multiple topics should be monitored. Note that this mechanism will - /// start the battery draining, and once started will keep drainig. + /// discharge. Any message on the specified topic will cause the battery to + /// start draining. This element can be specified multiple times if + /// multiple topics should be monitored. Note that this mechanism will + /// start the battery draining, and once started will keep drainig. /// - `` A topic that is used to stop battery - /// discharge. Any message on the specified topic will cause the battery to - /// stop draining. + /// discharge. Any message on the specified topic will cause the battery to + /// stop draining. class LinearBatteryPlugin : public System, diff --git a/src/systems/breadcrumbs/Breadcrumbs.hh b/src/systems/breadcrumbs/Breadcrumbs.hh index 5e5b3f64e4..0e09180263 100644 --- a/src/systems/breadcrumbs/Breadcrumbs.hh +++ b/src/systems/breadcrumbs/Breadcrumbs.hh @@ -56,7 +56,7 @@ namespace systems /// model using the `` tag. /// See the example in examples/worlds/breadcrumbs.sdf. /// - /// System Paramters + /// ## System Parameters /// /// - ``: Custom topic to be used to deploy breadcrumbs. If topic is /// not set, the default topic with the following pattern would be used @@ -82,7 +82,7 @@ namespace systems /// be deployed. Defaults to false. /// - ``: This is the model used as a template for deploying /// breadcrumbs. - /// ``: If true, then topic statistics are enabled on + /// - ``: If true, then topic statistics are enabled on /// `` and error messages will be generated when messages are /// dropped. Default to false. class Breadcrumbs diff --git a/src/systems/buoyancy/Buoyancy.hh b/src/systems/buoyancy/Buoyancy.hh index 5eae0f0864..bf89e01efb 100644 --- a/src/systems/buoyancy/Buoyancy.hh +++ b/src/systems/buoyancy/Buoyancy.hh @@ -67,7 +67,8 @@ namespace systems /// /// ## Examples /// - /// ### `uniform_fluid_density` world. + /// ### uniform_fluid_density world + /// /// The `buoyancy.sdf` SDF file contains three submarines. The first /// submarine is neutrally buoyant, the second sinks, and the third /// floats. To run: @@ -76,7 +77,7 @@ namespace systems /// gz sim -v 4 buoyancy.sdf /// ``` /// - /// ### `graded_buoyancy` world + /// ### graded_buoyancy world /// /// Often when simulating a maritime environment one may need to simulate both /// surface and underwater vessels. This means the buoyancy plugin needs to diff --git a/src/systems/buoyancy_engine/BuoyancyEngine.hh b/src/systems/buoyancy_engine/BuoyancyEngine.hh index ab0ad73324..422f5a703a 100644 --- a/src/systems/buoyancy_engine/BuoyancyEngine.hh +++ b/src/systems/buoyancy_engine/BuoyancyEngine.hh @@ -38,32 +38,35 @@ namespace systems /// `/model/{namespace}/buoyancy_engine` topic for the volume of the bladder /// in *cubicmeters*. /// - /// ## Parameters - /// - The link which the plugin is attached to [required, string] - /// - The namespace for the topic. If empty the plugin will listen - /// on `buoyancy_engine` otherwise it listens on + /// ## System Parameters + /// - ``: The link which the plugin is attached to [required, + /// string] + /// - ``: The namespace for the topic. If empty the plugin will + /// listen on `buoyancy_engine` otherwise it listens on /// `/model/{namespace}/buoyancy_engine` [optional, string] - /// - Minimum volume of the engine [optional, float, + /// - ``: Minimum volume of the engine [optional, float, /// default=0.00003m^3] - /// - At this volume the engine has neutral buoyancy. Used to - /// estimate the weight of the engine [optional, float, default=0.0003m^3] - /// - The volume which the engine starts at [optional, float, + /// - ``: At this volume the engine has neutral buoyancy. Used + /// to estimate the weight of the engine [optional, float, /// default=0.0003m^3] - /// - Maximum volume of the engine [optional, float, + /// - ``: The volume which the engine starts at [optional, + /// float, default=0.0003m^3] + /// - ``: Maximum volume of the engine [optional, float, /// default=0.00099m^3] - /// - Maximum inflation rate for bladder [optional, + /// - ``: Maximum inflation rate for bladder [optional, /// float, default=0.000003m^3/s] - /// - The fluid density of the liquid its suspended in kgm^-3. - /// [optional, float, default=1000kgm^-3] - /// - The Z height in metres at which the surface of the water is. - /// If not defined then there is no surface [optional, float] + /// - ``: The fluid density of the liquid its suspended in + /// kgm^-3. [optional, float, default=1000kgm^-3] + /// - ``: The Z height in metres at which the surface of the water + /// is. If not defined then there is no surface [optional, float] /// /// ## Topics - /// * Subscribes to a gz::msgs::Double on `buoyancy_engine` or - /// `/model/{namespace}/buoyancy_engine`. This is the set point for the - /// engine. - /// * Publishes a gz::msgs::Double on `buoyancy_engine` or - /// `/model/{namespace}/buoyancy_engine/current_volume` on the current volume + /// - Subscribes to a gz::msgs::Double on `buoyancy_engine` or + /// `/model/{namespace}/buoyancy_engine`. This is the set point for the + /// engine. + /// - Publishes a gz::msgs::Double on `buoyancy_engine` or + /// `/model/{namespace}/buoyancy_engine/current_volume` on the current + /// volume /// /// ## Examples /// To get started run: @@ -72,18 +75,18 @@ namespace systems /// ``` /// Enter the following in a separate terminal: /// ``` - /// gz topic -t /model/buoyant_box/buoyancy_engine/ -m gz.msgs.Double + /// gz topic -t /model/buoyant_box/buoyancy_engine/ -m gz.msgs.Double \ /// -p "data: 0.003" /// ``` - /// To see the box float up. + /// to see the box float up. /// ``` - /// gz topic -t /model/buoyant_box/buoyancy_engine/ -m gz.msgs.Double + /// 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 box go down. /// To see the current volume enter: /// ``` - /// gz topic -t /model/buoyant_box/buoyancy_engine/current_volume -e + /// gz topic -t /model/buoyant_box/buoyancy_engine/current_volume -e /// ``` class BuoyancyEnginePlugin: public gz::sim::System, diff --git a/src/systems/camera_video_recorder/CameraVideoRecorder.hh b/src/systems/camera_video_recorder/CameraVideoRecorder.hh index f19369cd13..2d3115e2a0 100644 --- a/src/systems/camera_video_recorder/CameraVideoRecorder.hh +++ b/src/systems/camera_video_recorder/CameraVideoRecorder.hh @@ -34,23 +34,25 @@ namespace systems /** \class CameraVideoRecorder CameraVideoRecorder.hh \ * gz/sim/systems/CameraVideoRecorder.hh **/ + /// /// \brief Record video from a camera sensor - /// The system takes in the following parameter: - /// Name of topic for the video recorder service. If this is - /// not specified, the topic defaults to: - /// /world//link// - /// sensor//record_video /// - /// True/false value that specifies if the video should - /// be recorded using simulation time or real time. The - /// default is false, which indicates the use of real - /// time. + /// ## System Parameters + /// + /// - ``: Name of topic for the video recorder service. If this is + /// not specified, the topic defaults to: + /// /world//link// + /// sensor//record_video + /// + /// - ``: True/false value that specifies if the video should + /// be recorded using simulation time or real time. The default is false, + /// which indicates the use of real time. /// - /// Video recorder frames per second. The default value is 25, and - /// the support type is unsigned int. + /// - ``: Video recorder frames per second. The default value is 25, and + /// the support type is unsigned int. /// - /// Video recorder bitrate (bps). The default value is - /// 2070000 bps, and the supported type is unsigned int. + /// - ``: Video recorder bitrate (bps). The default value is + /// 2070000 bps, and the supported type is unsigned int. class CameraVideoRecorder final: public System, public ISystemConfigure, diff --git a/src/systems/comms_endpoint/CommsEndpoint.hh b/src/systems/comms_endpoint/CommsEndpoint.hh index 30dacdb560..4e43b7bbba 100644 --- a/src/systems/comms_endpoint/CommsEndpoint.hh +++ b/src/systems/comms_endpoint/CommsEndpoint.hh @@ -36,22 +36,23 @@ namespace systems /// running. The system will bind this address in the broker automatically /// for you and unbind it when the model is destroyed. /// - /// The endpoint can be configured with the following SDF parameters: + /// ## System Parameters /// - /// * Required parameters: - ///
An identifier used to receive messages (string). - /// The topic name where you want to receive the messages targeted to - /// this address. + /// Required parameters: + /// - `
`: An identifier used to receive messages (string). + /// - ``: The topic name where you want to receive the messages + /// targeted to this address. /// - /// * Optional parameters: - /// Element used to capture where are the broker services. - /// This block can contain any of the next optional parameters: - /// : Service name used to bind an address. - /// The default value is "/broker/bind" - /// : Service name used to unbind from an address. - /// The default value is "/broker/unbind" + /// Optional parameters: + /// - ``: Element used to capture where are the broker services. + /// This block can contain any of the next optional parameters: + /// - ``: Service name used to bind an address. + /// The default value is "/broker/bind" + /// - ``: Service name used to unbind from an address. + /// The default value is "/broker/unbind" /// - /// Here's an example: + /// ## Example + /// ``` /// @@ -62,6 +63,7 @@ namespace systems /// /broker/unbind /// /// + /// ``` class CommsEndpoint : public System, public ISystemConfigure, diff --git a/src/systems/detachable_joint/DetachableJoint.hh b/src/systems/detachable_joint/DetachableJoint.hh index e6cb491285..c207b2d2ac 100644 --- a/src/systems/detachable_joint/DetachableJoint.hh +++ b/src/systems/detachable_joint/DetachableJoint.hh @@ -40,7 +40,7 @@ namespace systems /// model can be re-attached during simulation via a topic. The status of the /// detached state can be monitored via a topic as well. /// - /// Parameters: + /// ## System Parameters /// /// - ``: Name of the link in the parent model to be used in /// creating a fixed joint with a link in the child model. diff --git a/src/systems/diff_drive/DiffDrive.hh b/src/systems/diff_drive/DiffDrive.hh index 150621bb7c..0d16498e92 100644 --- a/src/systems/diff_drive/DiffDrive.hh +++ b/src/systems/diff_drive/DiffDrive.hh @@ -35,99 +35,99 @@ namespace systems /// \brief Differential drive controller which can be attached to a model /// with any number of left and right wheels. /// - /// # System Parameters + /// ## System Parameters /// - /// ``: Name of a joint that controls a left wheel. This + /// - ``: Name of a joint that controls a left wheel. This /// element can appear multiple times, and must appear at least once. /// - /// ``: Name of a joint that controls a right wheel. This + /// - ``: Name of a joint that controls a right wheel. This /// element can appear multiple times, and must appear at least once. /// - /// ``: Distance between wheels, in meters. This element + /// - ``: Distance between wheels, in meters. This element /// is optional, although it is recommended to be included with an /// appropriate value. The default value is 1.0m. /// - /// ``: Wheel radius in meters. This element is optional, + /// - ``: Wheel radius in meters. This element is optional, /// although it is recommended to be included with an appropriate value. The /// default value is 0.2m. /// - /// ``: Odometry publication frequency. This + /// - ``: Odometry publication frequency. This /// element is optional, and the default value is 50Hz. /// - /// ``: Custom topic that this system will subscribe to in order to + /// - ``: Custom topic that this system will subscribe to in order to /// receive command velocity messages. This element if optional, and the /// default value is `/model/{name_of_model}/cmd_vel`. /// - /// ``: Custom topic on which this system will publish odometry + /// - ``: Custom topic on which this system will publish odometry /// messages. This element if optional, and the default value is /// `/model/{name_of_model}/odometry`. /// - /// ``: Custom topic on which this system will publish the + /// - ``: Custom topic on which this system will publish the /// transform from `frame_id` to `child_frame_id`. This element is optional, /// and the default value is `/model/{name_of_model}/tf`. /// - /// ``: Custom `frame_id` field that this system will use as the + /// - ``: Custom `frame_id` field that this system will use as the /// origin of the odometry transform in both the `` - /// `gz.msgs.Pose_V` message and the `` - /// `gz.msgs.Odometry` message. This element if optional, and the + /// gz.msgs.Pose_V message and the `` + /// gz.msgs.Odometry message. This element if optional, and the /// default value is `{name_of_model}/odom`. /// - /// ``: Custom `child_frame_id` that this system will use as + /// - ``: Custom `child_frame_id` that this system will use as /// the target of the odometry trasnform in both the `` - /// `gz.msgs.Pose_V` message and the `` - /// `gz.msgs.Odometry` message. This element if optional, + /// gz.msgs.Pose_V message and the `` + /// gz.msgs.Odometry message. This element if optional, /// and the default value is `{name_of_model}/{name_of_link}`. /// - /// ``: Sets both the minimum linear and minimum angular + /// - ``: Sets both the minimum linear and minimum angular /// velocity. /// - /// ``: Sets both the maximum linear and maximum angular + /// - ``: Sets both the maximum linear and maximum angular /// velocity. /// - /// ``: Sets both the minimum linear and minimum angular + /// - ``: Sets both the minimum linear and minimum angular /// acceleration. /// - /// ``: Sets both the maximum linear and maximum angular + /// - ``: Sets both the maximum linear and maximum angular /// acceleration. /// - /// ``: Sets both the minimum linear and minimum angular jerk. + /// - ``: Sets both the minimum linear and minimum angular jerk. /// - /// ``: Sets both the maximum linear and maximum angular jerk. + /// - ``: Sets both the maximum linear and maximum angular jerk. /// - /// ``: Sets the minimum linear velocity. Overrides + /// - ``: Sets the minimum linear velocity. Overrides /// `` if set. /// - /// ``: Sets the maximum linear velocity. Overrides + /// - ``: Sets the maximum linear velocity. Overrides /// `` if set. /// - /// ``: Sets the minimum angular velocity. Overrides + /// - ``: Sets the minimum angular velocity. Overrides /// `` if set. /// - /// ``: Sets the maximum angular velocity. Overrides + /// - ``: Sets the maximum angular velocity. Overrides /// `` if set. /// - /// ``: Sets the minimum linear acceleration. + /// - ``: Sets the minimum linear acceleration. /// Overrides `` if set. /// - /// ``: Sets the maximum linear acceleration. + /// - ``: Sets the maximum linear acceleration. /// Overrides `` if set. /// - /// ``: Sets the minimum angular acceleration. + /// - ``: Sets the minimum angular acceleration. /// Overrides `` if set. /// - /// ``: Sets the maximum angular acceleration. + /// - ``: Sets the maximum angular acceleration. /// Overrides `` if set. /// - /// ``: Sets the minimum linear jerk. Overrides `` - /// if set. + /// - ``: Sets the minimum linear jerk. Overrides + /// `` if set. /// - /// ``: Sets the maximum linear jerk. Overrides `` - /// if set. + /// - ``: Sets the maximum linear jerk. Overrides + /// `` if set. /// - /// ``: Sets the minimum angular jerk. Overrides + /// - ``: Sets the minimum angular jerk. Overrides /// `` if set. /// - /// ``: Sets the maximum angular jerk. Overrides + /// - ``: Sets the maximum angular jerk. Overrides /// `` if set. class DiffDrive : public System, diff --git a/src/systems/elevator/Elevator.hh b/src/systems/elevator/Elevator.hh index 0fa6f0ea52..dc188795ee 100644 --- a/src/systems/elevator/Elevator.hh +++ b/src/systems/elevator/Elevator.hh @@ -69,37 +69,37 @@ class ElevatorPrivate; /// /// ## System Parameters /// -/// ``: System update rate. This element is optional and the +/// - ``: System update rate. This element is optional and the /// default value is 10Hz. A value of zero gets translated to the simulation /// rate (no throttling for the system). /// -/// ``: Prefix in the names of the links that function as +/// - ``: Prefix in the names of the links that function as /// a reference for each floor level. When the elevator is requested to move /// to a given floor level, the cabin is commanded to move to the height of /// the corresponding floor link. The names of the links will be expected to /// be `{prerix}i`, where \f$i=[0,N)\f$ and N is the number of floors. This /// element is optional and the default value is `floor_`. /// -/// ``: Prefix in the names of the joints that control the +/// - ``: Prefix in the names of the joints that control the /// doors of the elevator. The names of the joints will be expected to be /// `{prerix}i`, where \f$i=[0,N)\f$ and N is the number of floors. This /// element is optional and the default value is `door_`. /// -/// ``: Name of the joint that controls the position of the +/// - ``: Name of the joint that controls the position of the /// cabin. This element is optional and the default value is `lift`. /// -/// ``: Topic to which this system will subscribe in order to +/// - ``: Topic to which this system will subscribe in order to /// receive command messages. This element is optional and the default value /// is `/model/{model_name}/cmd`. /// -/// ``: Topic on which this system will publish state (current +/// - ``: Topic on which this system will publish state (current /// floor) messages. This element is optional and the default value is /// `/model/{model_name}/state`. /// -/// ``: State publication rate. This rate is bounded by +/// - ``: State publication rate. This rate is bounded by /// ``. This element is optional and the default value is 5Hz. /// -/// ``: Time to wait with a door open before the door +/// - ``: Time to wait with a door open before the door /// closes. This element is optional and the default value is 5 sec. class GZ_SIM_VISIBLE Elevator : public System, public ISystemConfigure, diff --git a/src/systems/environment_preload/EnvironmentPreload.hh b/src/systems/environment_preload/EnvironmentPreload.hh index 16a9793cc0..9b462281c1 100644 --- a/src/systems/environment_preload/EnvironmentPreload.hh +++ b/src/systems/environment_preload/EnvironmentPreload.hh @@ -32,8 +32,9 @@ namespace systems { class EnvironmentPreloadPrivate; - /// \class EnvironmentPreload EnvironmentPreload.hh - /// gz/sim/systems/EnvironmentPreload.hh + /** \class EnvironmentPreload EnvironmentPreload.hh \ + * gz/sim/systems/EnvironmentPreload.hh + **/ /// \brief A plugin to preload an Environment component /// into the ECM upon simulation start-up. class EnvironmentPreload : diff --git a/src/systems/follow_actor/FollowActor.hh b/src/systems/follow_actor/FollowActor.hh index 7a01a920cc..27076786c5 100644 --- a/src/systems/follow_actor/FollowActor.hh +++ b/src/systems/follow_actor/FollowActor.hh @@ -35,24 +35,23 @@ namespace systems /// \class FollowActor FollowActor.hh gz/sim/systems/FollowActor.hh /// \brief Make an actor follow a target entity in the world. /// - /// ## SDF parameters + /// ## System Parameters /// - /// : Name of entity to follow. + /// - ``: Name of entity to follow. /// - /// : Distance in meters to keep from target's origin. + /// - ``: Distance in meters to keep from target's origin. /// - /// : Distance in meters from target's origin when to stop - /// following. When the actor is back within range it starts - /// following again. + /// - ``: Distance in meters from target's origin when to stop + /// following. When the actor is back within range it starts following + /// again. /// - /// : Actor's velocity in m/s + /// - ``: Actor's velocity in m/s /// - /// : Actor's animation to play. If empty, the first animation in - /// the model will be used. + /// - ``: Actor's animation to play. If empty, the first animation + /// in the model will be used. /// - /// : Velocity of the animation on the X axis. Used to - /// coordinate translational motion with the actor's - /// animation. + /// - ``: Velocity of the animation on the X axis. Used to + /// coordinate translational motion with the actor's animation. class FollowActor: public System, public ISystemConfigure, diff --git a/src/systems/hydrodynamics/Hydrodynamics.hh b/src/systems/hydrodynamics/Hydrodynamics.hh index aab1a7cdb0..1ada82b467 100644 --- a/src/systems/hydrodynamics/Hydrodynamics.hh +++ b/src/systems/hydrodynamics/Hydrodynamics.hh @@ -40,7 +40,7 @@ namespace systems /// forces like linear and quadratic drag, buoyancy (not provided by this /// plugin), etc. /// - /// # System Parameters + /// ## System Parameters /// The exact description of these parameters can be found on p. 37 and /// p. 43 of Fossen's book. They are used to calculate added mass, linear and /// quadratic drag and coriolis force. diff --git a/src/systems/joint_controller/JointController.hh b/src/systems/joint_controller/JointController.hh index ae65473423..ec1b3bd381 100644 --- a/src/systems/joint_controller/JointController.hh +++ b/src/systems/joint_controller/JointController.hh @@ -37,56 +37,60 @@ namespace systems /// /// ## System Parameters /// - /// `` The name of the joint to control. Required parameter. + /// - `` The name of the joint to control. Required parameter. /// Can also include multiple `` for identical joints. /// - /// `` True to enable the controller implementation + /// - `` True to enable the controller implementation /// using force commands. If this parameter is not set or is false, the /// controller will use velocity commands internally. /// - /// `` True to enable the use of actuator message + /// - `` True to enable the use of actuator message /// for velocity command. The actuator msg is an array of floats for /// position, velocity and normalized commands. Relies on /// `` for the index of the velocity actuator and /// defaults to topic "/actuators" when `topic` or `subtopic not set. /// - /// `` used with `` to set + /// - `` used with `` to set /// the index of the velocity actuator. /// - /// `` Topic to receive commands in. Defaults to + /// - `` Topic to receive commands in. Defaults to /// `/model//joint//cmd_vel`. /// - /// `` Sub topic to receive commands in. - /// Defaults to "/model//". + /// - `` Sub topic to receive commands in. + /// Defaults to "/model//". /// - /// `` Velocity to start with. + /// - `` Velocity to start with. /// - /// ### Velocity mode: No additional parameters are required. + /// ### Velocity mode /// - /// ### Force mode: The controller accepts the next optional parameters: + /// No additional parameters are required. /// - /// `` The proportional gain of the PID. - /// The default value is 1. + /// ### Force mode /// - /// `` The integral gain of the PID. - /// The default value is 0. + /// The controller accepts the next optional parameters: /// - /// `` The derivative gain of the PID. - /// The default value is 0. + /// - `` The proportional gain of the PID. + /// The default value is 1. /// - /// `` The integral upper limit of the PID. - /// The default value is 1. + /// - `` The integral gain of the PID. + /// The default value is 0. + /// + /// - `` The derivative gain of the PID. + /// The default value is 0. + /// + /// - `` The integral upper limit of the PID. + /// The default value is 1. /// - /// `` The integral lower limit of the PID. - /// The default value is -1. + /// - `` The integral lower limit of the PID. + /// The default value is -1. /// - /// `` Output max value of the PID. - /// The default value is 1000. + /// - `` Output max value of the PID. + /// The default value is 1000. /// - /// `` Output min value of the PID. - /// The default value is -1000. + /// - `` Output min value of the PID. + /// The default value is -1000. /// - /// `` Command offset (feed-forward) of the PID. + /// - `` Command offset (feed-forward) of the PID. /// The default value is 0. class JointController : public System, diff --git a/src/systems/joint_position_controller/JointPositionController.hh b/src/systems/joint_position_controller/JointPositionController.hh index af139641d7..f7290fea29 100644 --- a/src/systems/joint_position_controller/JointPositionController.hh +++ b/src/systems/joint_position_controller/JointPositionController.hh @@ -46,56 +46,56 @@ namespace systems /// /// ## System Parameters /// - /// `` The name of the joint to control. Required parameter. - /// Can also include multiple `` for identical joints. + /// - `` The name of the joint to control. Required parameter. + /// Can also include multiple `` for identical joints. /// - /// `` Axis of the joint to control. Optional parameter. - /// The default value is 0. + /// - `` Axis of the joint to control. Optional parameter. + /// The default value is 0. /// - /// `` True to enable the use of actutor message + /// - `` True to enable the use of actutor message /// for position command. Relies on `` for the /// index of the position actuator and defaults to topic "/actuators". /// - /// `` used with `` to set + /// - `` used with `` to set /// the index of the position actuator. /// - /// `` The proportional gain of the PID. Optional parameter. - /// The default value is 1. + /// - `` The proportional gain of the PID. Optional parameter. + /// The default value is 1. /// - /// `` The integral gain of the PID. Optional parameter. - /// The default value is 0.1. + /// - `` The integral gain of the PID. Optional parameter. + /// The default value is 0.1. /// - /// `` The derivative gain of the PID. Optional parameter. - /// The default value is 0.01 + /// - `` The derivative gain of the PID. Optional parameter. + /// The default value is 0.01 /// - /// `` The integral upper limit of the PID. Optional parameter. - /// The default value is 1. + /// - `` The integral upper limit of the PID. Optional parameter. + /// The default value is 1. /// - /// `` The integral lower limit of the PID. Optional parameter. - /// The default value is -1. + /// - `` The integral lower limit of the PID. Optional parameter. + /// The default value is -1. /// - /// `` Output max value of the PID. Optional parameter. - /// The default value is 1000. + /// - `` Output max value of the PID. Optional parameter. + /// The default value is 1000. /// - /// `` Output min value of the PID. Optional parameter. - /// The default value is -1000. + /// - `` Output min value of the PID. Optional parameter. + /// The default value is -1000. /// - /// `` Command offset (feed-forward) of the PID. Optional + /// - `` Command offset (feed-forward) of the PID. Optional /// parameter. The default value is 0. /// - /// `` Bypasses the PID and creates a perfect + /// - `` Bypasses the PID and creates a perfect /// position. The maximum speed on the joint can be set using the `` /// tag. /// - /// `` If you wish to listen on a non-default topic you may specify it - /// here, otherwise the controller defaults to listening on + /// - `` If you wish to listen on a non-default topic you may specify + /// it here, otherwise the controller defaults to listening on /// "/model//joint///cmd_pos". /// - /// `` If you wish to listen on a sub_topic you may specify it + /// - `` If you wish to listen on a sub_topic you may specify it /// here "/model//". /// - /// `` Initial position of a joint. Optional parameter. - /// The default value is 0. + /// - `` Initial position of a joint. Optional parameter. + /// The default value is 0. class JointPositionController : public System, public ISystemConfigure, diff --git a/src/systems/joint_state_publisher/JointStatePublisher.hh b/src/systems/joint_state_publisher/JointStatePublisher.hh index 28d2408091..b92da24414 100644 --- a/src/systems/joint_state_publisher/JointStatePublisher.hh +++ b/src/systems/joint_state_publisher/JointStatePublisher.hh @@ -41,12 +41,13 @@ namespace systems /// a model. Use the `` system parameter, described below, to /// control which joints are published. /// - /// # System Parameters + /// ## System Parameters /// - /// ``: Name of the topic to publish to. This parameter is optional, + /// - ``: Name of the topic to publish to. This parameter is optional, /// and if not provided, the joint state will be published to /// "/world//model//joint_state". - /// ``: Name of a joint to publish. This parameter can be + /// + /// - ``: Name of a joint to publish. This parameter can be /// specified multiple times, and is optional. All joints in a model will /// be published if joint names are not specified. class JointStatePublisher diff --git a/src/systems/joint_traj_control/JointTrajectoryController.hh b/src/systems/joint_traj_control/JointTrajectoryController.hh index 09dc7d9e48..5c654e04e0 100644 --- a/src/systems/joint_traj_control/JointTrajectoryController.hh +++ b/src/systems/joint_traj_control/JointTrajectoryController.hh @@ -65,68 +65,68 @@ namespace systems /// /// ## System Parameters /// - /// `` The name of the topic that this plugin subscribes to. + /// - `` The name of the topic that this plugin subscribes to. /// Optional parameter. /// Defaults to "/model/${MODEL_NAME}/joint_trajectory". /// - /// `` If enabled, trajectory execution begins at the + /// - `` If enabled, trajectory execution begins at the /// timestamp contained in the header of received trajectory messages. /// Optional parameter. /// Defaults to false. /// - /// `` Name of a joint to control. + /// - `` Name of a joint to control. /// This parameter can be specified multiple times, i.e. once for each joint. /// Optional parameter. /// Defaults to all 1-axis joints contained in the model SDF (order is kept). /// - /// `` Initial position of a joint (for position control). + /// - `` Initial position of a joint (for position control). /// This parameter can be specified multiple times. Follows joint_name order. /// Optional parameter. /// Defaults to 0 for all joints. /// - /// `<%s_p_gain>` The proportional gain of the PID. + /// - `<%s_p_gain>` The proportional gain of the PID. /// Substitute '%s' for "position" or "velocity" (e.g. "position_p_gain"). /// This parameter can be specified multiple times. Follows joint_name order. /// Optional parameter. /// The default value is 0 (disabled). /// - /// `<%s_i_gain>` The integral gain of the PID. Optional parameter. + /// - `<%s_i_gain>` The integral gain of the PID. Optional parameter. /// Substitute '%s' for "position" or "velocity" (e.g. "position_p_gain"). /// This parameter can be specified multiple times. Follows joint_name order. /// Optional parameter. /// The default value is 0 (disabled). /// - /// `<%s_d_gain>` The derivative gain of the PID. + /// - `<%s_d_gain>` The derivative gain of the PID. /// Substitute '%s' for "position" or "velocity" (e.g. "position_p_gain"). /// This parameter can be specified multiple times. Follows joint_name order. /// Optional parameter. /// The default value is 0 (disabled). /// - /// `<%s_i_min>` The integral lower limit of the PID. + /// - `<%s_i_min>` The integral lower limit of the PID. /// Substitute '%s' for "position" or "velocity" (e.g. "position_p_gain"). /// This parameter can be specified multiple times. Follows joint_name order. /// Optional parameter. /// The default value is 0 (no limit if higher than `%s_i_max`). /// - /// `<%s_i_max>` The integral upper limit of the PID. + /// - `<%s_i_max>` The integral upper limit of the PID. /// Substitute '%s' for "position" or "velocity" (e.g. "position_p_gain"). /// This parameter can be specified multiple times. Follows joint_name order. /// Optional parameter. /// The default value is -1 (no limit if lower than `%s_i_min`). /// - /// `<%s_cmd_min>` Output min value of the PID. + /// - `<%s_cmd_min>` Output min value of the PID. /// Substitute '%s' for "position" or "velocity" (e.g. "position_p_gain"). /// This parameter can be specified multiple times. Follows joint_name order. /// Optional parameter. /// The default value is 0 (no limit if higher than `%s_i_max`). /// - /// `<%s_cmd_max>` Output max value of the PID. + /// - `<%s_cmd_max>` Output max value of the PID. /// Substitute '%s' for "position" or "velocity" (e.g. "position_p_gain"). /// This parameter can be specified multiple times. Follows joint_name order. /// Optional parameter. /// The default value is -1 (no limit if lower than `%s_i_min`). /// - /// `<%s_cmd_offset>` Command offset (feed-forward) of the PID. + /// - `<%s_cmd_offset>` Command offset (feed-forward) of the PID. /// Substitute '%s' for "position" or "velocity" (e.g. "position_p_gain"). /// This parameter can be specified multiple times. Follows joint_name order. /// Optional parameter. diff --git a/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.hh b/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.hh index c8d0020535..aae88a94eb 100644 --- a/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.hh +++ b/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.hh @@ -39,20 +39,20 @@ namespace systems /// that surpasses a specific threshold. /// This system can be used to detect when a model could be damaged. /// - /// # System Parameters + /// ## System Parameters /// - /// ``: Name of the link to monitor. This name must match + /// - ``: Name of the link to monitor. This name must match /// a name of link within the model. /// - /// ``: Threshold, in Joule (J), after which + /// - ``: Threshold, in Joule (J), after which /// a message is generated on `` with the kinetic energy value that /// surpassed the threshold. /// - /// ``: Custom topic that this system will publish to when kinetic + /// - ``: Custom topic that this system will publish to when kinetic /// energy surpasses the threshold. This element if optional, and the /// default value is `/model/{name_of_model}/kinetic_energy`. /// - /// # Example Usage + /// ## Example Usage /// /** \verbatim diff --git a/src/systems/lens_flare/LensFlare.hh b/src/systems/lens_flare/LensFlare.hh index 95ed7a07d4..9ea069d009 100644 --- a/src/systems/lens_flare/LensFlare.hh +++ b/src/systems/lens_flare/LensFlare.hh @@ -32,23 +32,26 @@ namespace systems /// \brief Private data class for LensFlare Plugin class LensFlarePrivate; - /** \class LensFlare LensFlare.hh \ + /** \class LensFlare LensFlare.hh \ * gz/sim/systems/LensFlare.hh **/ /// \brief Add lens flare effects to the camera output as a render pass - /// The system takes in the following parameter: - /// Sets the scale of the lens flare. If this is - /// not specified, the value defaults to 1.0 /// - /// Sets the color of the lens flare. The default - /// is {1.4, 1.2, 1.0} + /// ## System Parameters /// - /// Sets the number of steps to take in - /// each direction to check for occlusions. - /// The default value is set to 10. Use 0 to disable - /// Sets the light associated with the lens flares. - /// If not specified. The first light in the scene will - /// be used. + /// - ``: Sets the scale of the lens flare. If this is + /// not specified, the value defaults to 1.0 + /// + /// - ``: Sets the color of the lens flare. The default + /// is {1.4, 1.2, 1.0} + /// + /// - ``: Sets the number of steps to take in + /// each direction to check for occlusions. + /// The default value is set to 10. Use 0 to disable + /// + /// - ``: Sets the light associated with the lens flares. + /// If not specified. The first light in the scene will + /// be used. class LensFlare: public System, diff --git a/src/systems/lift_drag/LiftDrag.hh b/src/systems/lift_drag/LiftDrag.hh index 8c7cba996d..f9f33b960f 100644 --- a/src/systems/lift_drag/LiftDrag.hh +++ b/src/systems/lift_drag/LiftDrag.hh @@ -35,34 +35,35 @@ namespace systems /// \brief The LiftDrag system computes lift and drag forces enabling /// simulation of aerodynamic robots. /// - /// The following parameters are used by the system: + /// ## System Parameters /// - /// link_name : Name of the link affected by the group of lift/drag - /// properties. This can be a scoped name to reference links in - /// nested models. \sa entitiesFromScopedName to learn more - /// about scoped names. - /// air_density : Density of the fluid this model is suspended in. - /// area : Surface area of the link. - /// a0 : The initial "alpha" or initial angle of attack. a0 is also - /// the y-intercept of the alpha-lift coefficient curve. - /// cla : The ratio of the coefficient of lift and alpha slope before - /// stall. Slope of the first portion of the alpha-lift - /// coefficient curve. - /// cda : The ratio of the coefficient of drag and alpha slope before - /// stall. - /// cp : Center of pressure. The forces due to lift and drag will be - /// applied here. - /// forward : 3-vector representing the forward direction of motion in the - /// link frame. - /// upward : 3-vector representing the direction of lift or drag. - /// alpha_stall : Angle of attack at stall point; the peak angle of attack. - /// cla_stall : The ratio of coefficient of lift and alpha slope after - /// stall. Slope of the second portion of the alpha-lift - /// coefficient curve. - /// cda_stall : The ratio of coefficient of drag and alpha slope after - /// stall. - /// control_joint_name: Name of joint that actuates a control surface for this - /// lifting body (Optional) + /// - ``: Name of the link affected by the group of lift/drag + /// properties. This can be a scoped name to reference links in + /// nested models. \sa entitiesFromScopedName to learn more + /// about scoped names. + /// - ``: Density of the fluid this model is suspended in. + /// - ``: Surface area of the link. + /// - ``: The initial "alpha" or initial angle of attack. a0 is also + /// the y-intercept of the alpha-lift coefficient curve. + /// - ``: The ratio of the coefficient of lift and alpha slope before + /// stall. Slope of the first portion of the alpha-lift + /// coefficient curve. + /// - ``: The ratio of the coefficient of drag and alpha slope before + /// stall. + /// - ``: Center of pressure. The forces due to lift and drag will be + /// applied here. + /// - ``: 3-vector representing the forward direction of motion in + /// the link frame. + /// - ``: 3-vector representing the direction of lift or drag. + /// - ``: Angle of attack at stall point; the peak angle of + /// attack. + /// - ``: The ratio of coefficient of lift and alpha slope after + /// stall. Slope of the second portion of the alpha-lift + /// coefficient curve. + /// - ``: The ratio of coefficient of drag and alpha slope after + /// stall. + /// - ``: Name of joint that actuates a control surface + /// for this lifting body (Optional) class LiftDrag : public System, public ISystemConfigure, diff --git a/src/systems/log/LogPlayback.hh b/src/systems/log/LogPlayback.hh index bc8fd28110..66712a9c89 100644 --- a/src/systems/log/LogPlayback.hh +++ b/src/systems/log/LogPlayback.hh @@ -33,8 +33,9 @@ namespace systems // Forward declarations. class LogPlaybackPrivate; - /// \class LogPlayback LogPlayback.hh - /// gz/sim/systems/log/LogPlayback.hh + /** \class LogPlayback LogPlayback.hh \ + * gz/sim/systems/log/LogPlayback.hh + **/ /// \brief Log state playback class LogPlayback: public System, diff --git a/src/systems/log_video_recorder/LogVideoRecorder.hh b/src/systems/log_video_recorder/LogVideoRecorder.hh index 958f0152ce..0de7eb46ac 100644 --- a/src/systems/log_video_recorder/LogVideoRecorder.hh +++ b/src/systems/log_video_recorder/LogVideoRecorder.hh @@ -38,18 +38,21 @@ namespace systems /// \brief System which recordings videos from log playback /// There are two ways to specify what entities in the log playback to follow /// and record videos for: 1) by entity name and 2) by region. See the - /// following parameters: - /// - `` Name of entity to record. - /// - `` Axis-aligned box where entities are at start of log - /// + `` Min corner position of box region. - /// + `` Max corner position of box region. - /// - `` Sim time when recording should start - /// - `` Sim time when recording should end - /// - `` Exit gz-sim when log playback recording ends + /// system parameters. /// /// When recording is finished. An `end` string will be published to the /// `/log_video_recorder/status` topic and the videos are saved to a /// timestamped directory + /// + /// ## System Parameters + /// + /// - `` Name of entity to record. + /// - `` Axis-aligned box where entities are at start of log + /// + `` Min corner position of box region. + /// + `` Max corner position of box region. + /// - `` Sim time when recording should start + /// - `` Sim time when recording should end + /// - `` Exit gz-sim when log playback recording ends class LogVideoRecorder final: public System, public ISystemConfigure, diff --git a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh index 04c93edd45..0a4873d474 100644 --- a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh +++ b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh @@ -42,6 +42,8 @@ namespace systems /// such as speakers. This plugin is meant to check if audio /// could theoretically be heard at a certain location or not. /// + /// ## System Parameters + /// /// Secifying an audio source via SDF is done as follows: /// /// - `` A new audio source in the environment, which has the diff --git a/src/systems/mecanum_drive/MecanumDrive.hh b/src/systems/mecanum_drive/MecanumDrive.hh index 4cc910eee1..1442967687 100644 --- a/src/systems/mecanum_drive/MecanumDrive.hh +++ b/src/systems/mecanum_drive/MecanumDrive.hh @@ -35,58 +35,59 @@ namespace systems /// \brief Mecanum drive controller which can be attached to a model /// with any number of front/back left/right wheels. /// - /// # System Parameters + /// ## System Parameters /// - /// ``: Name of a joint that controls a front left wheel. + /// - ``: Name of a joint that controls a front left wheel. /// This element can appear multiple times, and must appear at least once. /// - /// ``: Name of a joint that controls a front right wheel. - /// This element can appear multiple times, and must appear at least once. + /// - ``: Name of a joint that controls a front right + /// wheel. This element can appear multiple times, and must appear at least + /// once. /// - /// ``: Name of a joint that controls a back left wheel. + /// - ``: Name of a joint that controls a back left wheel. /// This element can appear multiple times, and must appear at least once. /// - /// ``: Name of a joint that controls a back right wheel. + /// - ``: Name of a joint that controls a back right wheel. /// This element can appear multiple times, and must appear at least once. /// - /// ``: Longitudinal distance between front and back wheels, + /// - ``: Longitudinal distance between front and back wheels, /// in meters. This element is optional, although it is recommended to be /// included with an appropriate value. The default value is 1.0m. /// - /// ``: Lateral distance between left and right wheels, + /// - ``: Lateral distance between left and right wheels, /// in meters. This element is optional, although it is recommended to be /// included with an appropriate value. The default value is 1.0m. /// - /// ``: Wheel radius in meters. This element is optional, + /// - ``: Wheel radius in meters. This element is optional, /// although it is recommended to be included with an appropriate value. The /// default value is 0.2m. /// - /// ``: Odometry publication frequency. This + /// - ``: Odometry publication frequency. This /// element is optional, and the default value is 50Hz. /// - /// ``: Custom topic that this system will subscribe to in order to + /// - ``: Custom topic that this system will subscribe to in order to /// receive command velocity messages. This element if optional, and the /// default value is `/model/{name_of_model}/cmd_vel`. /// - /// ``: Custom topic on which this system will publish odometry + /// - ``: Custom topic on which this system will publish odometry /// messages. This element if optional, and the default value is /// `/model/{name_of_model}/odometry`. /// - /// ``: Custom topic on which this system will publish the + /// - ``: Custom topic on which this system will publish the /// transform from `frame_id` to `child_frame_id`. This element if optional, /// and the default value is `/model/{name_of_model}/tf`. /// - /// ``: Custom `frame_id` field that this system will use as the + /// - ``: Custom `frame_id` field that this system will use as the /// origin of the odometry transform in both the `` /// `gz.msgs.Pose_V` message and the `` /// `gz.msgs.Odometry` message. This element if optional, and the /// default value is `{name_of_model}/odom`. /// - /// ``: Custom `child_frame_id` that this system will use as + /// - ``: Custom `child_frame_id` that this system will use as /// the target of the odometry trasnform in both the `` /// `gz.msgs.Pose_V` message and the `` /// `gz.msgs.Odometry` message. This element if optional, - /// and the default value is `{name_of_model}/{name_of_link}`. + /// and the default value is `{name_of_model}/{name_of_link}`. class MecanumDrive : public System, public ISystemConfigure, diff --git a/src/systems/multicopter_control/MulticopterVelocityControl.hh b/src/systems/multicopter_control/MulticopterVelocityControl.hh index c414d1ec53..eb2cd1caf8 100644 --- a/src/systems/multicopter_control/MulticopterVelocityControl.hh +++ b/src/systems/multicopter_control/MulticopterVelocityControl.hh @@ -69,84 +69,85 @@ namespace systems /// * Maximum acceleration limit /// * Can be enabled/disabled at runtime. /// - /// # Parameters - /// The following parameters are used by the system + /// ## System Parameters /// - /// robotNamespace: All gz-transport topics subscribed to and published by - /// the system will be prefixed by this string. This is a required parameter. + /// - `robotNamespace`: All gz-transport topics subscribed to and published by + /// the system will be prefixed by this string. This is a required parameter. /// - /// commandSubTopic: The system subscribes to this topic to receive twist + /// - `commandSubTopic`: The system subscribes to this topic to receive twist /// commands. The default value is "cmd_vel". /// - /// enableSubTopic: Topic to enable or disable the system. If false, the + /// - `enableSubTopic`: Topic to enable or disable the system. If false, the /// controller sends a zero rotor velocity command once and gets disabled. If /// the vehicle is in the air, disabling the controller will cause it to fall. /// If true, the controller becomes enabled and waits for a twist message. The /// default value is "enable". /// - /// comLinkName: The link associated with the center of mass of the vehicle. - /// That is, the origin of the center of mass may not be on this link, but - /// this link and the center of mass frame have a fixed transform. Almost - /// always this should be the base_link of the vehicle. This is a required - /// parameter. + /// - `comLinkName`: The link associated with the center of mass of the + /// vehicle. That is, the origin of the center of mass may not be on this + /// link, but this link and the center of mass frame have a fixed transform. + /// Almost always this should be the base_link of the vehicle. This is a + /// required parameter. /// - /// velocityGain (x, y, z): Proportional gain on linear velocity. + /// - `velocityGain` (x, y, z): Proportional gain on linear velocity. /// attitudeGain (roll, pitch, yaw): Proportional gain on attitude. This /// parameter is scaled by the inverse of the inertia matrix so two vehicles /// with different inertial characteristics may have the same gain if other /// parameters, such as the forceConstant, are kept the same. This is a /// required parameter. /// - /// angularRateGain (roll, pitch, yaw): Proportional gain on angular velocity. - /// Even though only the yaw angle velocity is controlled, proper gain values - /// for roll and pitch velocities must be specified. This parameter is scaled - /// by the inverse of the inertia matrix so two vehicles with different - /// inertial characteristics may have the same gain if other parameters, such - /// as the forceConstant, are kept the same. This is a required parameter. + /// - `angularRateGain` (roll, pitch, yaw): Proportional gain on angular + /// velocity. Even though only the yaw angle velocity is controlled, proper + /// gain values for roll and pitch velocities must be specified. This + /// parameter is scaled by the inverse of the inertia matrix so two vehicles + /// with different inertial characteristics may have the same gain if other + /// parameters, such as the forceConstant, are kept the same. This is a + /// required parameter. /// - /// maxLinearAcceleration (x, y, z): Maximum limit on linear acceleration. + /// - `maxLinearAcceleration` (x, y, z): Maximum limit on linear acceleration. /// The default value is DBL_MAX. /// - /// maximumLinearVelocity (x, y, z): Maximum commanded linear velocity. The - /// default value is DBL_MAX. - - /// maximumAngularVelocity (roll, pitch, yaw): Maximum commanded angular + /// - `maximumLinearVelocity` (x, y, z): Maximum commanded linear velocity. + /// The default value is DBL_MAX. + /// + /// - `maximumAngularVelocity` (roll, pitch, yaw): Maximum commanded angular /// velocity. The default value is DBL_MAX. /// - /// linearVelocityNoiseMean (x, y, z): Mean of Gaussian noise on linear + /// - `linearVelocityNoiseMean` (x, y, z): Mean of Gaussian noise on linear /// velocity values obtained from simulation. The default value is (0, 0, 0). /// - /// linearVelocityNoiseStdDev (x, y, z): Standard deviation of Gaussian noise - /// on linear values obtained from simulation. A value of 0 implies noise is - /// NOT applied to the component. The default value is (0, 0, 0). + /// - `linearVelocityNoiseStdDev` (x, y, z): Standard deviation of Gaussian + /// noise on linear values obtained from simulation. A value of 0 implies + /// noise is NOT applied to the component. The default value is (0, 0, 0). /// - /// angularVelocityNoiseMean (roll, pitch, yaw): Mean of Gaussian noise on + /// - `angularVelocityNoiseMean` (roll, pitch, yaw): Mean of Gaussian noise on /// angular velocity values obtained from simulation. The default value is (0, /// 0, 0). /// - /// angularVelocityNoiseStdDev (roll, pitch, yaw): Standard deviation of + /// - `angularVelocityNoiseStdDev` (roll, pitch, yaw): Standard deviation of /// gaussian noise on angular velocity values obtained from simulation. A /// value of 0 implies noise is NOT applied to the component. The default /// value is (0, 0, 0). /// - /// rotorConfiguration: This contains a list of `` elements for each - /// rotor in the vehicle. This is a required parameter. + /// - `rotorConfiguration`: This contains a list of `` elements for + /// each rotor in the vehicle. This is a required parameter. /// - /// rotor: Contains information about a rotor in the vehicle. All the + /// - `rotor`: Contains information about a rotor in the vehicle. All the /// elements of `` are required parameters. /// - /// jointName: The name of the joint associated with this rotor. + /// - `jointName`: The name of the joint associated with this rotor. /// - /// forceConstant: A constant that multiplies with the square of the + /// - `forceConstant`: A constant that multiplies with the square of the /// rotor's velocity to compute its thrust. /// - /// momentConstant: A constant the multiplies with the rotor's thrust to - /// compute its moment. + /// - `momentConstant`: A constant the multiplies with the rotor's + /// thrust to compute its moment. + /// + /// - `direction`: Direction of rotation of the rotor. +1 is + /// counterclockwise and -1 is clockwise. /// - /// direction: Direction of rotation of the rotor. +1 is counterclockwise - /// and -1 is clockwise. + /// ## Examples /// - /// # Examples /// See examples/worlds/quadcopter.sdf for a demonstration. /// class MulticopterVelocityControl diff --git a/src/systems/pose_publisher/PosePublisher.hh b/src/systems/pose_publisher/PosePublisher.hh index db1a7e1d33..022ba2d4e6 100644 --- a/src/systems/pose_publisher/PosePublisher.hh +++ b/src/systems/pose_publisher/PosePublisher.hh @@ -37,33 +37,27 @@ namespace systems /// messages, or a single gz::msgs::Pose_V message if /// "use_pose_vector_msg" is true. /// - /// The following parameters are used by the system: + /// ## System Parameters /// - /// publish_link_pose : Set to true to publish link pose - /// publish_visual_pose : Set to true to publish visual pose - /// publish_collision_pose : Set to true to publish collision pose - /// publish_sensor_pose : Set to true to publish sensor pose - /// publish_model_pose : Set to true to publish model pose. - /// publish_nested_model_pose : Set to true to publish nested model pose. The - /// pose of the model that contains this system is - /// also published unless publish_model_pose is - /// set to false - /// use_pose_vector_msg : Set to true to publish an - /// gz::msgs::Pose_V message instead of - /// mulitple gz::msgs::Pose messages. - /// update_frequency : Frequency of pose publications in Hz. A - /// negative frequency publishes as fast as - /// possible (i.e, at the rate of the simulation - /// step) - /// static_publisher : Set to true to publish static poses on - /// a "/pose_static" topic. - /// This will cause only dynamic poses to be - /// published on the "/pose" - /// topic. - /// static_update_frequency : Frequency of static pose publications in Hz. A - /// negative frequency publishes as fast as - /// possible (i.e, at the rate of the simulation - /// step). + /// - ``: Set to true to publish link pose + /// - ``: Set to true to publish visual pose + /// - ``: Set to true to publish collision pose + /// - ``: Set to true to publish sensor pose + /// - ``: Set to true to publish model pose. + /// - ``: Set to true to publish nested model + /// pose. The pose of the model that contains this system is also published + /// unless publish_model_pose is set to false + /// - ``: Set to true to publish a gz::msgs::Pose_V + /// message instead of mulitple gz::msgs::Pose messages. + /// - ``: Frequency of pose publications in Hz. A negative + /// frequency publishes as fast as possible (i.e, at the rate of the + /// simulation step) + /// - ``: Set to true to publish static poses on a + /// "/pose_static" topic. This will cause only dynamic + /// poses to be published on the "/pose" topic. + /// - ``: Frequency of static pose publications in + /// Hz. A negative frequency publishes as fast as possible (i.e, at the + /// rate of the simulation step). class PosePublisher : public System, public ISystemConfigure, diff --git a/src/systems/user_commands/UserCommands.hh b/src/systems/user_commands/UserCommands.hh index f035c684a4..0aa396bd00 100644 --- a/src/systems/user_commands/UserCommands.hh +++ b/src/systems/user_commands/UserCommands.hh @@ -38,38 +38,38 @@ namespace systems /// \todo(louise) In the future, an interface undo/redo commands will also /// be provided. /// - /// # Spawn entity + /// ### Spawn entity /// /// * **Service**: `/world//create` - /// * **Request type*: gz.msgs.EntityFactory - /// * **Response type*: gz.msgs.Boolean + /// * **Request type**: gz.msgs.EntityFactory + /// * **Response type**: gz.msgs.Boolean /// - /// # Spawn multiple entities + /// ### Spawn multiple entities /// /// This service can spawn multiple entities in the same iteration, /// thereby eliminating simulation steps between entity spawn times. /// /// * **Service**: `/world//create_multiple` - /// * **Request type*: gz.msgs.EntityFactory_V - /// * **Response type*: gz.msgs.Boolean + /// * **Request type**: gz.msgs.EntityFactory_V + /// * **Response type**: gz.msgs.Boolean /// - /// # Set entity pose + /// ### Set entity pose /// /// This service set the pose of entities /// /// * **Service**: `/world//set_pose` - /// * **Request type*: gz.msgs.Pose - /// * **Response type*: gz.msgs.Boolean + /// * **Request type**: gz.msgs.Pose + /// * **Response type**: gz.msgs.Boolean /// - /// # Set multiple entity poses + /// ### Set multiple entity poses /// /// This service set the pose of multiple entities /// /// * **Service**: `/world//set_pose_vector` - /// * **Request type*: gz.msgs.Pose_V - /// * **Response type*: gz.msgs.Boolean + /// * **Request type**: gz.msgs.Pose_V + /// * **Response type**: gz.msgs.Boolean /// - /// Try some examples described on examples/worlds/empty.sdf + /// Try some examples described in examples/worlds/empty.sdf class UserCommands final: public System, public ISystemConfigure,