|
class | AckermannSteering |
| Ackermann steering controller which can be attached to a model with any number of left and right wheels. More...
|
|
class | AcousticComms |
| A comms model that simulates communication using acoustic devices. The model uses simple distance based acoustics model. More...
|
|
class | AdvancedLiftDrag |
| The LiftDrag system computes lift and drag forces enabling simulation of aerodynamic robots. More...
|
|
class | AirPressure |
| An air pressure sensor that reports vertical position and velocity readings over gz transport. More...
|
|
class | AirSpeed |
| An air speed sensor that reports vertical position and velocity readings over gz transport. More...
|
|
class | Altimeter |
| An altimeter sensor that reports vertical position and velocity readings over gz transport. More...
|
|
class | ApplyJointForce |
| This system applies a force to the first axis of a specified joint. More...
|
|
class | ApplyLinkWrench |
| Exposes transport topics and SDF params for applying forces and torques to links in simulation. It should be attached to a world. More...
|
|
class | Breadcrumbs |
| A system for creating Breadcrumbs in the form of models that can get deployed/spawned at the location of the model to which this system is attached. Each breadcrumb is a complete sdf::Model. When deployed, the pose of the breadcrumb model is offset from the containing model by the pose specified in the <pose> element of the breadcrumb model. A name is generated for the breadcrumb by appending the current count of deployments to the name specified in the breadcrumb <model> element. The model specified in the <breadcrumb> parameter serves as a template for deploying multiple breadcrumbs of the same type. Including models from Fuel is accomplished by creating a <model> that includes the Fuel model using the <include> tag. See the example in examples/worlds/breadcrumbs.sdf. More...
|
|
class | Buoyancy |
| A system that simulates buoyancy of objects immersed in fluid. All SDF parameters are optional. This system must be attached to the world and this system will apply buoyancy to all links that have collision shapes. More...
|
|
class | BuoyancyEnginePlugin |
| This class provides a simple mechanical bladder which is used to control the buoyancy of an underwater glider. It uses Archimedes' principle to apply an upward force based on the volume of the bladder. It listens to the topic buoyancy_engine or /model/{namespace}/buoyancy_engine topic for the volume of the bladder in cubicmeters. More...
|
|
class | CameraVideoRecorder |
| 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. More...
|
|
class | ColladaWorldExporter |
| A plugin that exports a world to a mesh. When loaded the plugin will dump a mesh containing all the models in the world to the current directory. More...
|
|
class | CommsEndpoint |
| A system that registers in the comms broker an endpoint. You're creating an address attached to the model where the plugin is running. The system will bind this address in the broker automatically for you and unbind it when the model is destroyed. More...
|
|
class | Contact |
| Contact sensor system which manages all contact sensors in simulation. More...
|
|
class | DetachableJoint |
| A system that initially attaches two models via a fixed joint and allows for the models to get detached during simulation via a topic. A model can be re-attached during simulation via a topic. The status of the detached state can be monitored via a topic as well. More...
|
|
class | DiffDrive |
| Differential drive controller which can be attached to a model with any number of left and right wheels. More...
|
|
class | DoorTimer |
| Timer that's used to keep a door open. It has a configurable default wait duration that when exceeded, it calls a function to let the state machine know to transition to the next state. The timer also checks whether the doorway is blocked, in which case it keeps the door open until whatever blocks the doorway moves out of the way. More...
|
|
class | Elevator |
| System that controls an elevator. It closely models the structure and functionality of a real elevator. It individually controls the cabin and doors of the elevator, queues commands for the elevator and stops at intermediate floors if a command is received while the last one is ongoing, and keeps a door open if the doorway is blocked. The model of the elevator can have arbitrarily many floor levels and at arbitrary heights each. More...
|
|
class | ElevatorStateMachineDef |
| Elevator state machine frontend. Defines the transition table and initial state of the state machine. More...
|
|
class | ElevatorStateMachinePrivate |
|
class | EnvironmentPreload |
| A plugin to preload an Environment component into the ECM upon simulation start-up. More...
|
|
class | FollowActor |
| Make an actor follow a target entity in the world. More...
|
|
class | ForceTorque |
| This system manages all Force-Torque sensors in simulation. Each FT sensor reports readings over Gazebo Transport. More...
|
|
class | Hydrodynamics |
| This class provides hydrodynamic behaviour for underwater vehicles It is shamelessly based off Brian Bingham's plugin for VRX. which in turn is based of Fossen's equations described in "Guidance and
Control of Ocean Vehicles" [1]. The class should be used together with the buoyancy plugin to help simulate behaviour of maritime vehicles. Hydrodynamics refers to the behaviour of bodies in water. It includes forces like linear and quadratic drag, buoyancy (not provided by this plugin), etc. More...
|
|
class | Imu |
| This system manages all IMU sensors in simulation. Each IMU sensor eports vertical position, angular velocity and lienar acceleration readings over Gazebo Transport. More...
|
|
class | JointController |
| Joint controller which can be attached to a model with a reference to a single joint. Currently only the first axis of a joint is actuated. More...
|
|
class | JointMonitor |
| Monitor that checks the state of a joint. When the joint reaches the configured target, it calls a function to let the state machine know to transition to the next state. More...
|
|
class | JointPositionController |
| Joint position controller which can be attached to a model with a reference to a single joint. More...
|
|
class | JointStatePublisher |
| The JointStatePublisher system publishes joint state information for a model. The published message type is gz::msgs::Model, and the publication topic is determined by the <topic> parameter. More...
|
|
class | JointTrajectoryController |
| Joint trajectory controller, which can be attached to a model with reference to one or more 1-axis joints in order to follow a trajectory. More...
|
|
class | KineticEnergyMonitor |
| A system that monitors the kinetic energy of a link in a model and publishes when there is a lost of kinetic energy during a timestep that surpasses a specific threshold. This system can be used to detect when a model could be damaged. More...
|
|
class | Label |
| A label plugin that annotates models by setting the label for the parent entity's visuals. The plugin can be attached to models, visuals, or actors. More...
|
|
class | LiftDrag |
| The LiftDrag system computes lift and drag forces enabling simulation of aerodynamic robots. More...
|
|
class | LighterThanAirDynamics |
| This class provides the effect of viscousity on the hull of lighter-than-air vehicles such as airships. The equations implemented is based on the work published in [1], which describes a modeling approach for the nonlinear dynamics simulation of airships and [2] providing more insight of the modelling of an airship. More...
|
|
class | LinearBatteryPlugin |
| A plugin for simulating battery usage. More...
|
|
class | LogicalAudioSensorPlugin |
| A plugin for logical audio detection. More...
|
|
class | LogicalCamera |
| A logical camera sensor that reports objects detected within its frustum readings over gz transport. More...
|
|
class | LogPlayback |
| Log state playback. More...
|
|
class | LogRecord |
| Log state recorder. More...
|
|
class | LogVideoRecorder |
| 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: More...
|
|
class | Magnetometer |
| An magnetometer sensor that reports the magnetic field in its current location. More...
|
|
class | MecanumDrive |
| Mecanum drive controller which can be attached to a model with any number of front/back left/right wheels. More...
|
|
class | ModelPhotoShoot |
| This plugin is a port of the old ModelPropShop plugin from gazebo classic. It generates 5 pictures of a model: perspective, top, front, side and back. It can do it using the default position or moving the joint to random positions. It allows saving the camera and joint poses so it can be replicated in other systems. More...
|
|
class | MulticopterMotorModel |
| This system applies a thrust force to models with spinning propellers. See examples/worlds/quadcopter.sdf for a demonstration. More...
|
|
class | MulticopterVelocityControl |
| This is a velocity controller for multicopters that allows control over the linear velocity and the yaw angular velocity of the vehicle. The velocities are expressed in the body frame of the vehicle. A vehicle with at least 4 rotors is required for the controller to function. More...
|
|
class | NavSat |
| System that handles navigation satellite sensors, such as GPS, that reports position and velocity in spherical coordinates (latitude / longitude) over Gazebo Transport. More...
|
|
class | OdometryPublisher |
| Odometry Publisher which can be attached to any entity in order to periodically publish 2D or 3D odometry data in the form of gz::msgs::Odometry messages. More...
|
|
class | OpticalTactilePlugin |
| Plugin that implements an optical tactile sensor. More...
|
|
class | ParticleEmitter |
| A system for running and managing particle emitters. A particle emitter is defined using the <particle_emitter> SDF element. More...
|
|
class | ParticleEmitter2 |
| This is deprecated, please use the ParticleEmitter system. A system for running and managing particle emitters. A particle emitter is defined using the <particle_emitter> SDF element. More...
|
|
class | PerfectComms |
| An example of a comms model. This model always delivers any message to its destination. More...
|
|
class | PerformerDetector |
| A system system that publishes on a topic when a performer enters or leaves a specified region. More...
|
|
class | Physics |
| Base class for a System. Includes optional parameter : <include_entity_names>. When set to false, the name of colliding entities is not populated in the contacts. Remains true by default. Usage : More...
|
|
class | PosePublisher |
| Pose publisher system. Attach to an entity to publish the transform of its child entities in the form of gz::msgs::Pose messages, or a single gz::msgs::Pose_V message if "use_pose_vector_msg" is true. More...
|
|
class | RFComms |
| A comms model that simulates communication using radio frequency (RF) devices. The model uses a log-distance path loss function. More...
|
|
class | SceneBroadcaster |
| System which periodically publishes a gz::msgs::Scene message with updated information. More...
|
|
class | Sensors |
| A system that manages sensors. More...
|
|
class | ShaderParam |
| A plugin for setting shaders to a visual and its params. More...
|
|
class | SpacecraftThrusterModel |
| This system applies a thrust force to models with RCS-like thrusters. See tutorials/spacecraft_thrusters.md for a tutorial usage. Below follow the minimum necessary parameters needed by the plugin: More...
|
|
class | Thermal |
| A thermal plugin that sets the temperature for the parent entity. More...
|
|
class | ThermalSensor |
| A thermal sensor plugin for configuring thermal sensor properties. More...
|
|
class | Thruster |
| This plugin simulates a maritime thruster for boats and underwater vehicles. It uses the equations described in Fossen's "Guidance and Control of Ocean Vehicles" in page 246. This plugin has two modes of operation. In the default mode it takes in a force in Newtons and applies it to the thruster. It also calculates the theoretical angular velocity of the blades and spins them accordingly. Alternatively, one may send angular velocity commands to calculate the force to be applied using the said equation. In the default mode the plugin will publish angular velocity in radians per second on /model/{ns}/joint/{joint_name}/ang_vel as a gz.msgs.double. If <use_angvel_cmd> is set to true it publishes force in Newtons instead to /model/{ns}/joint/{joint_name}/force . More...
|
|
class | TouchPlugin |
| Plugin which publishes a message if the model it is attached to has touched one or more specified targets continuously during a given time. More...
|
|
class | TrackController |
| Controller of a track on either a conveyor belt or a tracked vehicle. The system should be attached to a model. If implementing a tracked vehicle, use also TrackedVehicle system. More...
|
|
class | TrackedVehicle |
| Tracked vehicle controller which can be attached to a model with any number of left and right tracks. The system should be attached to a model. Each track has to have a TrackController system configured and running. More...
|
|
class | TrajectoryFollower |
| A plugin that scripts the movement of a model based on waypoints. Note that at this point, the trajectory is always in 2D (x, y). The plugin applies a torque until the model is aligned with the next waypoint. Then, it applies a force until the model is close enough to the waypoint. More...
|
|
class | TriggeredPublisher |
| The triggered publisher system publishes a user specified message on an output topic in response to an input message that matches user specified criteria. It can also call a user specified service as an output in response to an input message. It currently supports blocking service call. An optional simulation time delay can be used delay message publication. More...
|
|
class | UserCommands |
| This system provides a Gazebo Transport interface to execute commands while simulation is running. More...
|
|
class | VelocityControl |
| Linear and angular velocity controller which is directly set on a model. More...
|
|
class | WheelSlip |
| A system that updates wheel slip parameters based on linear wheel spin velocity (radius * spin rate). It currently assumes that the fdir1 friction parameter is set parallel to the joint axis (often [0 0 1]) and that the link origin is on the joint axis. The slip parameter is a Force-Dependent Slip (slip1, slip2) and it has units of velocity / force (m / s / N), similar to the inverse of a viscous damping coefficient. The slip_compliance parameters specified in this plugin are unitless, representing the lateral or longitudinal slip ratio (see https://en.wikipedia.org/wiki/Slip_(vehicle_dynamics) ) to tangential force ratio (tangential / normal force). Note that the maximum force ratio is the friction coefficient. At each time step, these compliances are multiplied by the linear wheel spin velocity and divided by the wheel_normal_force parameter specified below in order to match the units of the slip parameters. More...
|
|
class | WindEffects |
| A system that simulates a simple wind model. The wind is described as a uniform worldwide model. Its components are computed separately: More...
|
|
Namespace for all System plugins. Refer to the System class for more information about systems.