Forward declarations for the common classes. More...
Namespaces | |
client | |
common | |
Common namespace. | |
event | |
Event namespace. | |
gui | |
gui namespace | |
msgs | |
Messages namespace. | |
physics | |
namespace for physics | |
rendering | |
Rendering namespace. | |
sensors | |
Sensors namespace. | |
transport | |
util | |
Classes | |
class | ActorPlugin |
class | ActuatorPlugin |
Plugin for simulating a torque-speed curve for actuators. More... | |
class | ActuatorProperties |
Properties for a model of a rotational actuator. More... | |
class | AmbientOcclusionVisualPlugin |
Plugin that creates an ambient occlusion effect The current implementation uses the Crease Shading method ported from OGRE. More... | |
class | ArduCopterPlugin |
Interface ArduCopter from ardupilot stack modeled after SITL/SIM_*. More... | |
class | ArrangePlugin |
class | AttachLightPlugin |
A model plugin that enables multiple lights in the world to be attached to links within the model. More... | |
class | BlinkVisualPlugin |
Plugin that makes a visual blink between two colors. More... | |
class | BreakableJointPlugin |
A plugin for breakable joints, based on a ForceTorque sensor plugin. More... | |
class | BuoyancyPlugin |
A plugin that simulates buoyancy of an object immersed in fluid. More... | |
class | CameraPlugin |
class | CartDemoPlugin |
This plugin drives a four wheeled cart model forward and back by applying a small wheel torque. More... | |
class | CessnaGUIPlugin |
A GUI plugin that controls the Cessna model using the keyboard. More... | |
class | CessnaPlugin |
Allow moving the control surfaces of a Cessna C-172 plane. More... | |
class | ContactPlugin |
A plugin for a contact sensor. More... | |
class | ContainPlugin |
Plugin which emits Ignition Transport messages according to whether an entity's origin is inside or outside a given volume. More... | |
class | DepthCameraPlugin |
class | DiffDrivePlugin |
class | ElevatorPlugin |
Plugin to control a elevator. More... | |
class | EventSource |
The base class for emitting SimEvents. More... | |
class | ExistenceEventSource |
class | FiducialCameraPlugin |
A camera sensor plugin for fiducial detection A fiducial is detected if its center is within the camera frustum and not occluded by other models in the view. More... | |
class | FlashLightPlugin |
A plugin that blinks a light component in the model. More... | |
class | FlashLightSetting |
Internal data class to hold individual flash light settings. More... | |
class | FollowerPlugin |
A simple object follower that finds the closest object in a depth image and commands a differential drive vehicle to move towards the object. More... | |
class | ForceTorquePlugin |
An base class plugin for custom force torque sensor processing. More... | |
class | GimbalSmall2dPlugin |
A plugin for controlling the angle of a gimbal joint. More... | |
class | GpuRayPlugin |
class | GravityCompensationPlugin |
Plugin that provides gravity compensation. More... | |
class | GUIPlugin |
A plugin loaded within the gzclient on startup. More... | |
class | HarnessPlugin |
This plugin is designed to lower a model at a controlled rate. More... | |
class | HeightmapLODPlugin |
Plugin that sets the heightmap LOD. More... | |
class | HydraDemoPlugin |
class | ImuSensorPlugin |
An base class plugin for custom imu sensor processing. More... | |
class | InitialVelocityPlugin |
class | InRegionEventSource |
The event generator class. More... | |
class | JointControlPlugin |
Plugin that initializes joint controllers. More... | |
class | JointEventSource |
The event generator class. More... | |
class | JointTrajectoryPlugin |
class | JoyPlugin |
The JoyPlugin connects to a joystick or gamepad, and transmits data from the joystick over an Ignition Transport topic. More... | |
class | KeyboardGUIPlugin |
A GUI plugin that captures key strokes from gzclient GUI and publishes over gz transport topic ~/keyboard/keypress More... | |
struct | KeyInfo |
Store information from SDF for each key. More... | |
class | KeysToCmdVelPlugin |
Send velocity commands to a model based on keypress messages received. More... | |
class | KeysToJointsPlugin |
Control joints in a model based on keypress messages received. More... | |
class | LedPlugin |
A plugin that blinks light and visual elements in a model. More... | |
class | LedSetting |
Internal data class to hold individual LED light settings. More... | |
class | LensFlareSensorPlugin |
Plugin that adds lens flare effect to a camera or multicamera sensor The plugin has the following optional parameter: <scale> Scale of lens flare. More... | |
class | LiftDragPlugin |
A plugin that simulates lift and drag. More... | |
class | LinearBatteryConsumerPlugin |
A plugin that manages a linear battery consumer. More... | |
class | LinearBatteryPlugin |
A plugin that simulates a linear battery. More... | |
class | LinkPlot3DPlugin |
A plugin that traces the trajectory of a link in the rendering scene. More... | |
class | LookAtDemoPlugin |
A GUI plugin that demos the ignition::math::Matrix4<T>::LookAt function. More... | |
class | Master |
A manager that directs topic connections, enables each gazebo network client to locate one another for peer-to-peer communication. More... | |
class | MisalignmentPlugin |
Plugin which emits gazebo transport message indicating the alignment of two poses. More... | |
class | ModelPlugin |
A plugin with access to physics::Model. More... | |
class | ModelPropShop |
This plugin will generate 5 pictures of a model: perspective, top, front, side, back. More... | |
class | ModelResourceRetriever |
class | MudPlugin |
class | OccupiedEventSource |
A plugin that transmits a message when an in-region event occurs. More... | |
class | PlaneDemoPlugin |
A plugin that simulates lift and drag. More... | |
class | PluginT |
A class which all plugins must inherit from. More... | |
class | PressurePlugin |
A plugin for a tactile pressure sensor. More... | |
class | RandomVelocityPlugin |
Plugin that applies a random velocity to a linke periodically. More... | |
class | RayPlugin |
A Ray Sensor Plugin. More... | |
class | RaySensorNoisePlugin |
A Ray Sensor Noise Plugin. More... | |
class | RazerHydra |
class | Region |
A region, made of a list of boxes. More... | |
class | RegionEventBoxPlugin |
A plugin that fires an event when another model enters the region defined by the size of this model's box visual. More... | |
class | RenderingFixture |
class | RestApi |
REST interface. More... | |
class | RestException |
class | RestUiPlugin |
REST user interface plugin. More... | |
class | RestUiWidget |
REST user interface widget. More... | |
class | RestWebPlugin |
REST web plugin. More... | |
class | RubblePlugin |
class | SensorPlugin |
A plugin with access to physics::Sensor. More... | |
class | Server |
class | ServerFixture |
class | ShaderParamVisualPlugin |
A plugin that demonstrates how to set shader parameters of a material used by a visual. More... | |
class | SimEventConnector |
Gazebo events to detect model creation/deletion. More... | |
class | SimEventsException |
class | SimEventsPlugin |
class | SimpleTrackedVehiclePlugin |
A very fast, but also very accurate model of non-deformable tracks without grousers. More... | |
class | SimStateEventSource |
SimEvent that fires when the simulation is paused/resumed. More... | |
class | SkidSteerDrivePlugin |
A gazebo model plugin that controls a four wheel skid-steer robot via a gazebo topic. More... | |
class | SonarPlugin |
A sonar sensor plugin. More... | |
class | SphereAtlasDemoPlugin |
class | StaticMapPlugin |
A plugin that creates a model with textured map images. More... | |
class | StopWorldPlugin |
This plugin will stop the world. More... | |
class | SystemPlugin |
A plugin loaded within the gzserver on startup. More... | |
class | TimerGUIPlugin |
A GUI plugin that displays a timer. More... | |
class | TouchPlugin |
Plugin which checks if this model has touched some specific target for a given time continuously and exclusively. More... | |
class | TrackedVehiclePlugin |
An abstract gazebo model plugin for tracked vehicles. More... | |
class | TransporterPlugin |
A plugin that allows models to transport (teleport) to a new location. More... | |
class | VariableGearboxPlugin |
A plugin that uses piecewise cubic Hermite splines to support arbitrary smooth input-output relationships between the input and output angles of a gearbox. More... | |
class | VehiclePlugin |
class | VisualPlugin |
A plugin with access to rendering::Visual. More... | |
class | VolumeProperties |
A class for storing the volume properties of a link. More... | |
class | WheelSlipPlugin |
A plugin that updates ODE wheel slip parameters based on linear wheel spin velocity (radius * spin rate). More... | |
class | WheelTrackedVehiclePlugin |
An approximate model of non-deformable tracks emulated by wheels. More... | |
class | WindPlugin |
A plugin that simulates a simple wind model. More... | |
class | WorldPlugin |
A plugin with access to physics::World. More... | |
Typedefs | |
typedef std::shared_ptr< EventSource > | EventSourcePtr |
typedef boost::shared_ptr< GUIPlugin > | GUIPluginPtr |
typedef boost::shared_ptr< ModelPlugin > | ModelPluginPtr |
using | ModelResourceRetrieverPtr = std::shared_ptr< ModelResourceRetriever > |
typedef std::shared_ptr< Region > | RegionPtr |
typedef boost::shared_ptr< SensorPlugin > | SensorPluginPtr |
typedef boost::shared_ptr< SystemPlugin > | SystemPluginPtr |
typedef boost::shared_ptr< VisualPlugin > | VisualPluginPtr |
typedef boost::shared_ptr< WorldPlugin > | WorldPluginPtr |
Enumerations | |
enum | PluginType { WORLD_PLUGIN, MODEL_PLUGIN, SENSOR_PLUGIN, SYSTEM_PLUGIN, VISUAL_PLUGIN, GUI_PLUGIN } |
Used to specify the type of plugin. More... | |
enum | Tracks : bool { LEFT, RIGHT } |
Enum for distinguishing between left and right tracks. More... | |
Functions | |
GAZEBO_VISIBLE void | addPlugin (const std::string &_filename) |
Add a system plugin. More... | |
std::string | custom_exec (std::string _cmd) |
GAZEBO_VISIBLE gazebo::physics::WorldPtr | loadWorld (const std::string &_worldFile) |
Create and load a new world from an SDF world file. More... | |
GAZEBO_VISIBLE void | printVersion () |
Output version information to the terminal. More... | |
GAZEBO_VISIBLE void | runWorld (gazebo::physics::WorldPtr _world, unsigned int _iterations) |
Run a world for a specific number of iterations. More... | |
GAZEBO_VISIBLE bool | setupServer (int _argc=0, char **_argv=0) |
Start a gazebo server. More... | |
GAZEBO_VISIBLE bool | setupServer (const std::vector< std::string > &_args) |
Start a gazebo server. More... | |
GAZEBO_VISIBLE bool | shutdown () |
Stop and cleanup simulation. More... | |
Forward declarations for the common classes.
Example SDF: <plugin name="actuator_plugin" filename="libActuatorPlugin.so"> <actuator> <name>actuator_0</name> <joint>JOINT_0</joint> <index>0</index> <type>electric_motor</type> <power>20</power> <max_velocity>6</max_velocity> <max_torque>10.0</max_torque> </actuator> </plugin> </model>
Forward declarations for the util classes.
Required fields:
typedef std::shared_ptr<EventSource> EventSourcePtr |
typedef boost::shared_ptr<GUIPlugin> GUIPluginPtr |
typedef boost::shared_ptr<ModelPlugin> ModelPluginPtr |
using ModelResourceRetrieverPtr = std::shared_ptr<ModelResourceRetriever> |
typedef boost::shared_ptr<SensorPlugin> SensorPluginPtr |
typedef boost::shared_ptr<SystemPlugin> SystemPluginPtr |
typedef boost::shared_ptr<VisualPlugin> VisualPluginPtr |
typedef boost::shared_ptr<WorldPlugin> WorldPluginPtr |
|
strong |
GAZEBO_VISIBLE void gazebo::addPlugin | ( | const std::string & | _filename | ) |
Add a system plugin.
[in] | _filename | Path to the plugin. |
std::string gazebo::custom_exec | ( | std::string | _cmd | ) |
GAZEBO_VISIBLE gazebo::physics::WorldPtr gazebo::loadWorld | ( | const std::string & | _worldFile | ) |
Create and load a new world from an SDF world file.
[in] | _worldFile | The world file to load from. |
GAZEBO_VISIBLE void gazebo::printVersion | ( | ) |
Output version information to the terminal.
GAZEBO_VISIBLE void gazebo::runWorld | ( | gazebo::physics::WorldPtr | _world, |
unsigned int | _iterations | ||
) |
Run a world for a specific number of iterations.
[in] | _world | Pointer to a world. |
[in] | _iterations | Number of iterations to execute. |
GAZEBO_VISIBLE bool gazebo::setupServer | ( | int | _argc = 0 , |
char ** | _argv = 0 |
||
) |
Start a gazebo server.
This starts transportation, and makes it possible to create worlds.
[in] | _argc | Number of commandline arguments. |
[in] | _argv | The commandline arguments. |
GAZEBO_VISIBLE bool gazebo::setupServer | ( | const std::vector< std::string > & | _args | ) |
Start a gazebo server.
This starts transportation, and makes it possible to create worlds.
[in] | _args | Vector of arguments only parsed by the system plugins. Note that when you run gazebo/gzserver, all the options (–version, –server-plugin, etc.) are parsed but when using Gazebo as a library, the arguments are only parsed by the system plugins. |
GAZEBO_VISIBLE bool gazebo::shutdown | ( | ) |
Stop and cleanup simulation.
Referenced by Connection::ConnectToShutdown().