Skip to content

Commit

Permalink
Merge branch 'gz-sim8' into mabelzhang/component_tutorial
Browse files Browse the repository at this point in the history
  • Loading branch information
mabelzhang committed Nov 1, 2023
2 parents 27198c5 + d693df6 commit 2e8d6ea
Show file tree
Hide file tree
Showing 29 changed files with 400 additions and 378 deletions.
2 changes: 1 addition & 1 deletion examples/plugin/custom_sensor_system/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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})
Expand Down
72 changes: 36 additions & 36 deletions src/systems/ackermann_steering/AckermannSteering.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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
///
/// `<steering_only>`: Boolean used to only control the steering angle
/// - `<steering_only>`: 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
/// `<use_actuator_msg>` is True, uses defaults topic name "/actuators".
///
/// `<use_actuator_msg>` True to enable the use of actutor message
/// - `<use_actuator_msg>` True to enable the use of actutor message
/// for steering angle command. Relies on `<actuator_number>` for the
/// index of the position actuator and defaults to topic "/actuators".
///
/// `<actuator_number>` used with `<use_actuator_commands>` to set
/// - `<actuator_number>` used with `<use_actuator_commands>` to set
/// the index of the steering angle position actuator.
///
/// `<steer_p_gain>`: Float used to control the steering angle P gain.
/// - `<steer_p_gain>`: Float used to control the steering angle P gain.
/// Only used for when in steering_only mode.
///
/// `<left_joint>`: Name of a joint that controls a left wheel. This
/// - `<left_joint>`: Name of a joint that controls a left wheel. This
/// element can appear multiple times, and must appear at least once.
///
/// `<right_joint>`: Name of a joint that controls a right wheel. This
/// - `<right_joint>`: Name of a joint that controls a right wheel. This
/// element can appear multiple times, and must appear at least once.
///
/// `<left_steering_joint>`: 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.
/// - `<left_steering_joint>`: 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.
///
/// `<right_steering_joint>`: Name of a joint that controls steering for
/// right wheel. This element must appear once.
/// - `<right_steering_joint>`: Name of a joint that controls steering for
/// right wheel. This element must appear once.
///
/// `<wheel_separation>`: Distance between wheels, in meters. This element
/// - `<wheel_separation>`: 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.
///
/// `<kingpin_width>`: Distance between wheel kingpins, in meters. This
/// - `<kingpin_width>`: 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.
///
/// `<wheel_base>`: Distance between front and rear wheels, in meters. This
/// - `<wheel_base>`: 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.
///
/// `<steering_limit>`: Value to limit steering to. Can be calculated by
/// - `<steering_limit>`: 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>`: Wheel radius in meters. This element is optional,
/// - `<wheel_radius>`: 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.
///
/// `<odom_publish_frequency>`: Odometry publication frequency. This
/// - `<odom_publish_frequency>`: Odometry publication frequency. This
/// element is optional, and the default value is 50Hz.
///
/// `<min_velocity>`: Minimum velocity [m/s], usually <= 0.
/// `<max_velocity>`: Maximum velocity [m/s], usually >= 0.
/// `<min_acceleration>`: Minimum acceleration [m/s^2], usually <= 0.
/// `<max_acceleration>`: Maximum acceleration [m/s^2], usually >= 0.
/// `<min_jerk Minimum>`: jerk [m/s^3], usually <= 0.
/// `<max_jerk Maximum>`: jerk [m/s^3], usually >= 0.
/// - `<min_velocity>`: Minimum velocity [m/s], usually <= 0.
/// - `<max_velocity>`: Maximum velocity [m/s], usually >= 0.
/// - `<min_acceleration>`: Minimum acceleration [m/s^2], usually <= 0.
/// - `<max_acceleration>`: Maximum acceleration [m/s^2], usually >= 0.
/// - `<min_jerk Minimum>`: jerk [m/s^3], usually <= 0.
/// - `<max_jerk Maximum>`: jerk [m/s^3], usually >= 0.
///
/// `<topic>`: Custom topic that this system will subscribe to in order to
/// - `<topic>`: 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`.
///
/// `<sub_topic>`: Custom sub_topic that this system will subscribe to in
/// - `<sub_topic>`: 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}`
///
/// `<odom_topic>`: Custom topic on which this system will publish odometry
/// - `<odom_topic>`: Custom topic on which this system will publish odometry
/// messages. This element if optional, and the default value is
/// `/model/{name_of_model}/odometry`.
///
/// `<tf_topic>`: Custom topic on which this system will publish the
/// - `<tf_topic>`: 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`.
///
/// `<frame_id>`: Custom `frame_id` field that this system will use as the
/// - `<frame_id>`: Custom `frame_id` field that this system will use as the
/// origin of the odometry transform in both the `<tf_topic>`
/// `gz.msgs.Pose_V` message and the `<odom_topic>`
/// `gz.msgs.Odometry` message. This element if optional, and the
/// default value is `{name_of_model}/odom`.
///
/// `<child_frame_id>`: Custom `child_frame_id` that this system will use as
/// - `<child_frame_id>`: Custom `child_frame_id` that this system will use as
/// the target of the odometry transform in both the `<tf_topic>`
/// `gz.msgs.Pose_V` message and the `<odom_topic>`
/// `gz.msgs.Odometry` message. This element if optional,
/// gz.msgs.Pose_V message and the `<odom_topic>`
/// 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
Expand Down
2 changes: 2 additions & 0 deletions src/systems/acoustic_comms/AcousticComms.hh
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,7 @@ namespace systems
/// * <seed> : Seed value to be used for random sampling.
///
/// Here's an example:
/// ```
/// <plugin
/// filename="gz-sim-acoustic-comms-system"
/// name="gz::sim::systems::AcousticComms">
Expand All @@ -93,6 +94,7 @@ namespace systems
/// </propagation_model>
///
/// </plugin>
/// ```

class AcousticComms:
public gz::sim::comms::ICommsModel
Expand Down
27 changes: 14 additions & 13 deletions src/systems/battery_plugin/LinearBatteryPlugin.hh
Original file line number Diff line number Diff line change
Expand Up @@ -39,35 +39,36 @@ namespace systems

/// \brief A plugin for simulating battery usage
///
/// This system processes the following sdf parameters:
/// ## System parameters
///
/// - `<battery_name>` name of the battery (required)
/// - `<voltage>` Initial voltage of the battery (required)
/// - `<open_circuit_voltage_constant_coef>` Voltage at full charge
/// - `<open_circuit_voltage_linear_coef>` Amount of voltage decrease when no
/// charge
/// charge
/// - `<initial_charge>` Initial charge of the battery (Ah)
/// - `<capacity>` Total charge that the battery can hold (Ah)
/// - `<resistance>` Internal resistance (Ohm)
/// - `<smooth_current_tau>` coefficient for smoothing current [0, 1].
/// - `<power_load>` power load on battery (required) (Watts)
/// - `<enable_recharge>` If true, the battery can be recharged
/// - `<recharge_by_topic>` 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.
/// - `<charging_time>` Hours taken to fully charge the battery.
/// (Required if `<enable_recharge>` is set to true)
/// (Required if `<enable_recharge>` is set to true)
/// - `<fix_issue_225>` 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.
/// - `<start_drainign>` Whether to start draining the battery right away.
/// False by default.
/// False by default.
/// - `<power_draining_topic>` 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.
/// - `<stop_power_draining_topic>` 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,
Expand Down
4 changes: 2 additions & 2 deletions src/systems/breadcrumbs/Breadcrumbs.hh
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ namespace systems
/// model using the `<include>` tag.
/// See the example in examples/worlds/breadcrumbs.sdf.
///
/// System Paramters
/// ## System Parameters
///
/// - `<topic>`: Custom topic to be used to deploy breadcrumbs. If topic is
/// not set, the default topic with the following pattern would be used
Expand All @@ -82,7 +82,7 @@ namespace systems
/// be deployed. Defaults to false.
/// - `<breadcrumb>`: This is the model used as a template for deploying
/// breadcrumbs.
/// `<topic_statistics>`: If true, then topic statistics are enabled on
/// - `<topic_statistics>`: If true, then topic statistics are enabled on
/// `<topic>` and error messages will be generated when messages are
/// dropped. Default to false.
class Breadcrumbs
Expand Down
5 changes: 3 additions & 2 deletions src/systems/buoyancy/Buoyancy.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand All @@ -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
Expand Down
51 changes: 27 additions & 24 deletions src/systems/buoyancy_engine/BuoyancyEngine.hh
Original file line number Diff line number Diff line change
Expand Up @@ -38,32 +38,35 @@ namespace systems
/// `/model/{namespace}/buoyancy_engine` topic for the volume of the bladder
/// in *cubicmeters*.
///
/// ## Parameters
/// <link_name> - The link which the plugin is attached to [required, string]
/// <namespace> - The namespace for the topic. If empty the plugin will listen
/// on `buoyancy_engine` otherwise it listens on
/// ## System Parameters
/// - `<link_name>`: The link which the plugin is attached to [required,
/// string]
/// - `<namespace>`: The namespace for the topic. If empty the plugin will
/// listen on `buoyancy_engine` otherwise it listens on
/// `/model/{namespace}/buoyancy_engine` [optional, string]
/// <min_volume> - Minimum volume of the engine [optional, float,
/// - `<min_volume>`: Minimum volume of the engine [optional, float,
/// default=0.00003m^3]
/// <neutral_volume> - At this volume the engine has neutral buoyancy. Used to
/// estimate the weight of the engine [optional, float, default=0.0003m^3]
/// <default_volume> - The volume which the engine starts at [optional, float,
/// - `<neutral_volume>`: At this volume the engine has neutral buoyancy. Used
/// to estimate the weight of the engine [optional, float,
/// default=0.0003m^3]
/// <max_volume> - Maximum volume of the engine [optional, float,
/// - `<default_volume>`: The volume which the engine starts at [optional,
/// float, default=0.0003m^3]
/// - `<max_volume>`: Maximum volume of the engine [optional, float,
/// default=0.00099m^3]
/// <max_inflation_rate> - Maximum inflation rate for bladder [optional,
/// - `<max_inflation_rate>`: Maximum inflation rate for bladder [optional,
/// float, default=0.000003m^3/s]
/// <fluid_density> - The fluid density of the liquid its suspended in kgm^-3.
/// [optional, float, default=1000kgm^-3]
/// <surface> - The Z height in metres at which the surface of the water is.
/// If not defined then there is no surface [optional, float]
/// - `<fluid_density>`: The fluid density of the liquid its suspended in
/// kgm^-3. [optional, float, default=1000kgm^-3]
/// - `<surface>`: 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:
Expand All @@ -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,
Expand Down
28 changes: 15 additions & 13 deletions src/systems/camera_video_recorder/CameraVideoRecorder.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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:
/// <service> Name of topic for the video recorder service. If this is
/// not specified, the topic defaults to:
/// /world/<world_name/model/<model_name>/link/<link_name>/
/// sensor/<sensor_name>/record_video
///
/// <use_sim_time> 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
///
/// - `<service>`: Name of topic for the video recorder service. If this is
/// not specified, the topic defaults to:
/// /world/<world_name/model/<model_name>/link/<link_name>/
/// sensor/<sensor_name>/record_video
///
/// - `<use_sim_time>`: 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.
///
/// <fps> Video recorder frames per second. The default value is 25, and
/// the support type is unsigned int.
/// - `<fps>`: Video recorder frames per second. The default value is 25, and
/// the support type is unsigned int.
///
/// <bitrate> Video recorder bitrate (bps). The default value is
/// 2070000 bps, and the supported type is unsigned int.
/// - `<bitrate>`: Video recorder bitrate (bps). The default value is
/// 2070000 bps, and the supported type is unsigned int.
class CameraVideoRecorder final:
public System,
public ISystemConfigure,
Expand Down
Loading

0 comments on commit 2e8d6ea

Please sign in to comment.