gazebo::physics Namespace Reference

namespace for physics More...

Classes

class  Actor
 Actor class enables GPU based mesh model / skeleton scriptable animation. More...
 
class  AdiabaticAtmosphere
 Adiabatic atmosphere model based on the troposphere model in the Manual of the ICAO Standard Atmosphere. More...
 
class  Atmosphere
 This models a base atmosphere class to serve as a common interface to any derived atmosphere models. More...
 
class  AtmosphereFactory
 The atmosphere factory instantiates different atmosphere models. More...
 
class  BallJoint
 Base class for a ball joint. More...
 
class  Base
 Base class for most physics classes. More...
 
class  BoxShape
 Box geometry primitive. More...
 
class  BulletBallJoint
 BulletBallJoint class models a ball joint in Bullet. More...
 
class  BulletBoxShape
 Bullet box collision. More...
 
class  BulletCollision
 Bullet collisions. More...
 
class  BulletCylinderShape
 Cylinder collision. More...
 
class  BulletFixedJoint
 A fixed joint. More...
 
class  BulletHeightmapShape
 Height map collision. More...
 
class  BulletHinge2Joint
 A two axis hinge joint. More...
 
class  BulletHingeJoint
 A single axis hinge joint. More...
 
class  BulletJoint
 Base class for all joints. More...
 
class  BulletLink
 Bullet Link class. More...
 
class  BulletMesh
 Triangle mesh collision helper class. More...
 
class  BulletMeshShape
 Triangle mesh collision. More...
 
class  BulletMotionState
 Bullet btMotionState encapsulation. More...
 
class  BulletMultiRayShape
 Bullet specific version of MultiRayShape. More...
 
class  BulletPhysics
 Bullet physics engine. More...
 
class  BulletPlaneShape
 Bullet collision for an infinite plane. More...
 
class  BulletPolylineShape
 Bullet polyline shape. More...
 
class  BulletRayShape
 Ray shape for bullet. More...
 
class  BulletScrewJoint
 A screw joint. More...
 
class  BulletSliderJoint
 A slider joint. More...
 
class  BulletSphereShape
 Bullet sphere collision. More...
 
class  BulletSurfaceParams
 Bullet surface parameters. More...
 
class  BulletTypes
 A set of functions for converting between the math types used by gazebo and bullet. More...
 
class  BulletUniversalJoint
 A bullet universal joint class. More...
 
class  Collision
 Base class for all collision entities. More...
 
class  CollisionState
 Store state information of a physics::Collision object. More...
 
class  Contact
 A contact between two collisions. More...
 
class  ContactManager
 Aggregates all the contact information generated by the collision detection engine. More...
 
class  ContactPublisher
 A custom contact publisher created for each contact filter in the Contact Manager. More...
 
class  CylinderShape
 Cylinder collision. More...
 
class  DARTBallJoint
 An DARTBallJoint. More...
 
class  DARTBoxShape
 DART Box shape. More...
 
class  DARTCollision
 Base class for all DART collisions. More...
 
class  DARTCylinderShape
 DART cylinder shape. More...
 
class  DARTFixedJoint
 A single axis hinge joint. More...
 
class  DARTHeightmapShape
 DART Height map collision. More...
 
class  DARTHeightmapShapePrivate
 Forward declare private data class. More...
 
class  DARTHinge2Joint
 A two axis hinge joint. More...
 
class  DARTHingeJoint
 A single axis hinge joint. More...
 
class  DARTJoint
 DART joint interface. More...
 
class  DARTLink
 DART Link class. More...
 
class  DARTMesh
 Triangle mesh collision helper class. More...
 
class  DARTMeshShape
 Triangle mesh collision. More...
 
class  DARTModel
 DART model class. More...
 
class  DARTMultiRayShape
 DART specific version of MultiRayShape. More...
 
class  DARTPhysics
 DART physics engine. More...
 
class  DARTPlaneShape
 An DART Plane shape. More...
 
class  DARTPolylineShape
 DART polyline shape. More...
 
class  DARTRayShape
 Ray collision. More...
 
class  DARTScrewJoint
 A screw joint. More...
 
class  DARTSliderJoint
 A slider joint. More...
 
class  DARTSphereShape
 A DART sphere shape. More...
 
class  DARTSurfaceParams
 DART surface parameters. More...
 
class  DARTTypes
 A set of functions for converting between the math types used by gazebo and dart. More...
 
class  DARTUniversalJoint
 A universal joint. More...
 
class  Entity
 Base class for all physics objects in Gazebo. More...
 
class  FixedJoint
 A fixed joint rigidly connecting two bodies. More...
 
class  FrictionPyramid
 Parameters used for friction pyramid model. More...
 
class  GearboxJoint
 A double axis gearbox joint. More...
 
class  Gripper
 A gripper abstraction. More...
 
class  HeightmapShape
 HeightmapShape collision shape builds a heightmap from an image. More...
 
class  Hinge2Joint
 A two axis hinge joint. More...
 
class  HingeJoint
 A single axis hinge joint. More...
 
class  Inertial
 A class for inertial information about a link. More...
 
class  Joint
 Base class for all joints. More...
 
class  JointController
 A class for manipulating physics::Joint. More...
 
class  JointState
 keeps track of state of a physics::Joint More...
 
class  JointWrench
 Wrench information from a joint. More...
 
class  Light
 A light entity. More...
 
class  LightState
 Store state information of a Light object. More...
 
class  Link
 Link class defines a rigid body entity, containing information on inertia, visual and collision properties of a rigid body. More...
 
class  LinkState
 Store state information of a physics::Link object. More...
 
class  MapShape
 Creates box extrusions based on an image. More...
 
class  MeshShape
 Triangle mesh collision shape. More...
 
class  Model
 A model is a collection of links, joints, and plugins. More...
 
class  ModelState
 Store state information of a physics::Model object. More...
 
class  MultiRayShape
 Laser collision contains a set of ray-collisions, structured to simulate a laser range scanner. More...
 
class  ODEBallJoint
 An ODEBallJoint. More...
 
class  ODEBoxShape
 ODE Box shape. More...
 
class  ODECollision
 Base class for all ODE collisions. More...
 
class  ODECylinderShape
 ODE cylinder shape. More...
 
class  ODEFixedJoint
 A fixed joint. More...
 
class  ODEGearboxJoint
 A double axis gearbox joint. More...
 
class  ODEHeightmapShape
 ODE Height map collision. More...
 
class  ODEHinge2Joint
 A two axis hinge joint. More...
 
class  ODEHingeJoint
 A single axis hinge joint. More...
 
class  ODEJoint
 ODE joint interface. More...
 
class  ODELink
 ODE Link class. More...
 
class  ODEMesh
 Triangle mesh helper class. More...
 
class  ODEMeshShape
 Triangle mesh collision. More...
 
class  ODEMultiRayShape
 ODE specific version of MultiRayShape. More...
 
class  ODEPhysics
 ODE physics engine. More...
 
class  ODEPlaneShape
 An ODE Plane shape. More...
 
class  ODEPolylineShape
 ODE polyline shape. More...
 
class  ODERayShape
 Ray collision. More...
 
class  ODEScrewJoint
 A screw joint. More...
 
class  ODESliderJoint
 A slider joint. More...
 
class  ODESphereShape
 A ODE sphere shape. More...
 
class  ODESurfaceParams
 ODE surface parameters. More...
 
class  ODEUniversalJoint
 A universal joint. More...
 
class  PhysicsEngine
 Base class for a physics engine. More...
 
class  PhysicsFactory
 The physics factory instantiates different physics engines. More...
 
class  PlaneShape
 Collision for an infinite plane. More...
 
class  PolylineShape
 Polyline geometry primitive. More...
 
class  Population
 Class that automatically populates an environment with multiple objects based on several parameters to define the number of objects, shape of the object distribution or type of distribution. More...
 
class  PopulationParams
 Stores all the posible parameters that define a population. More...
 
class  Preset
 Representation of a preset physics profile. More...
 
class  PresetManager
 Class to manage preset physics profiles. More...
 
class  RayShape
 Base class for Ray collision geometry. More...
 
class  Road
 for building a Road from SDF More...
 
class  ScrewJoint
 A screw joint, which has both prismatic and rotational DOFs. More...
 
class  Shape
 Base class for all shapes. More...
 
class  SimbodyBallJoint
 SimbodyBallJoint class models a ball joint in Simbody. More...
 
class  SimbodyBoxShape
 Simbody box collision. More...
 
class  SimbodyCollision
 Simbody collisions. More...
 
class  SimbodyCylinderShape
 Cylinder collision. More...
 
class  SimbodyFixedJoint
 A fixed joint rigidly connecting two bodies. More...
 
class  SimbodyHeightmapShape
 Height map collision. More...
 
class  SimbodyHinge2Joint
 A two axis hinge joint. More...
 
class  SimbodyHingeJoint
 A single axis hinge joint. More...
 
class  SimbodyJoint
 Base class for all joints. More...
 
class  SimbodyLink
 Simbody Link class. More...
 
class  SimbodyMesh
 Triangle mesh collision helper class. More...
 
class  SimbodyMeshShape
 Triangle mesh collision. More...
 
class  SimbodyModel
 A model is a collection of links, joints, and plugins. More...
 
class  SimbodyMultiRayShape
 Simbody specific version of MultiRayShape. More...
 
class  SimbodyPhysics
 Simbody physics engine. More...
 
class  SimbodyPlaneShape
 Simbody collision for an infinite plane. More...
 
class  SimbodyPolylineShape
 Simbody polyline shape. More...
 
class  SimbodyRayShape
 Ray shape for simbody. More...
 
class  SimbodyScrewJoint
 A screw joint. More...
 
class  SimbodySliderJoint
 A slider joint. More...
 
class  SimbodySphereShape
 Simbody sphere collision. More...
 
class  SimbodyUniversalJoint
 A simbody universal joint class. More...
 
class  SliderJoint
 A slider joint. More...
 
class  SphereShape
 Sphere collision shape. More...
 
class  State
 State of an entity. More...
 
class  SurfaceParams
 SurfaceParams defines various Surface contact parameters. More...
 
class  TrajectoryInfo
 Information about a trajectory for an Actor. More...
 
class  UniversalJoint
 A universal joint. More...
 
class  UserCmd
 Class which represents a user command, which can be "undone" and "redone". More...
 
class  UserCmdManager
 Manages user commands from the server side. More...
 
class  Wind
 Base class for wind. More...
 
class  World
 The world provides access to all other object within a simulated environment. More...
 
class  WorldState
 Store state information of a physics::World object. More...
 

Typedefs

typedef std::vector< ActorPtrActor_V
 
typedef boost::shared_ptr< ActorActorPtr
 
typedef std::unique_ptr< Atmosphere >(* AtmosphereFactoryFn) (World &world)
 
typedef std::vector< BasePtrBase_V
 
typedef boost::shared_ptr< BaseBasePtr
 
typedef boost::shared_ptr< BoxShapeBoxShapePtr
 
typedef boost::shared_ptr< BulletCollisionBulletCollisionPtr
 
typedef boost::shared_ptr< BulletLinkBulletLinkPtr
 
typedef boost::shared_ptr< BulletMotionStateBulletMotionStatePtr
 
typedef boost::shared_ptr< BulletPhysicsBulletPhysicsPtr
 
typedef boost::shared_ptr< BulletRayShapeBulletRayShapePtr
 
typedef boost::shared_ptr< BulletSurfaceParamsBulletSurfaceParamsPtr
 
typedef std::vector< CollisionPtrCollision_V
 
typedef boost::shared_ptr< CollisionCollisionPtr
 
typedef boost::shared_ptr< ContactContactPtr
 
typedef boost::shared_ptr< CylinderShapeCylinderShapePtr
 
using DARTBodyNodePropPtr = std::shared_ptr< dart::dynamics::BodyNode::Properties >
 
typedef boost::shared_ptr< DARTCollisionDARTCollisionPtr
 
using DARTJointPropPtr = std::shared_ptr< dart::dynamics::Joint::Properties >
 
typedef boost::shared_ptr< DARTJointDARTJointPtr
 
typedef boost::shared_ptr< DARTLinkDARTLinkPtr
 
typedef boost::shared_ptr< DARTModelDARTModelPtr
 
typedef boost::shared_ptr< DARTPhysicsDARTPhysicsPtr
 
typedef boost::shared_ptr< DARTRayShapeDARTRayShapePtr
 
typedef boost::shared_ptr< DARTSurfaceParamsDARTSurfaceParamsPtr
 
typedef boost::shared_ptr< EntityEntityPtr
 
typedef boost::shared_ptr< FrictionPyramidFrictionPyramidPtr
 
typedef boost::shared_ptr< GripperGripperPtr
 
typedef boost::shared_ptr< HeightmapShapeHeightmapShapePtr
 
typedef boost::shared_ptr< InertialInertialPtr
 
typedef std::vector< JointPtrJoint_V
 
typedef std::vector< JointControllerPtrJointController_V
 
typedef boost::shared_ptr< JointControllerJointControllerPtr
 
typedef boost::shared_ptr< JointJointPtr
 
typedef std::map< std::string, JointStateJointState_M
 
typedef std::vector< LightPtrLight_V
 
typedef boost::shared_ptr< LightLightPtr
 
typedef std::map< std::string, LightStateLightState_M
 
typedef std::vector< LinkPtrLink_V
 
typedef boost::shared_ptr< LinkLinkPtr
 
typedef std::map< std::string, LinkStateLinkState_M
 
typedef boost::shared_ptr< MeshShapeMeshShapePtr
 
typedef std::vector< ModelPtrModel_V
 
typedef boost::shared_ptr< ModelModelPtr
 
typedef std::map< std::string, ModelStateModelState_M
 
typedef boost::shared_ptr< MultiRayShapeMultiRayShapePtr
 
typedef boost::shared_ptr< ODECollisionODECollisionPtr
 
typedef boost::shared_ptr< ODEJointODEJointPtr
 
typedef boost::shared_ptr< ODELinkODELinkPtr
 
typedef boost::shared_ptr< ODEPhysicsODEPhysicsPtr
 
typedef boost::shared_ptr< ODERayShapeODERayShapePtr
 
typedef boost::shared_ptr< ODESurfaceParamsODESurfaceParamsPtr
 
typedef boost::shared_ptr< PhysicsEnginePhysicsEnginePtr
 
typedef PhysicsEnginePtr(* PhysicsFactoryFn) (WorldPtr world)
 
typedef boost::shared_ptr< PlaneShapePlaneShapePtr
 
typedef boost::shared_ptr< PolylineShapePolylineShapePtr
 
typedef boost::shared_ptr< PresetManagerPresetManagerPtr
 
typedef boost::shared_ptr< RayShapeRayShapePtr
 
typedef boost::shared_ptr< RoadRoadPtr
 
typedef boost::shared_ptr< ShapeShapePtr
 
typedef boost::shared_ptr< SimbodyCollisionSimbodyCollisionPtr
 
typedef boost::shared_ptr< SimbodyLinkSimbodyLinkPtr
 
typedef boost::shared_ptr< SimbodyModelSimbodyModelPtr
 
typedef boost::shared_ptr< SimbodyPhysicsSimbodyPhysicsPtr
 
typedef boost::shared_ptr< SimbodyRayShapeSimbodyRayShapePtr
 
typedef boost::shared_ptr< SphereShapeSphereShapePtr
 
typedef boost::shared_ptr< SurfaceParamsSurfaceParamsPtr
 
typedef std::shared_ptr< TrajectoryInfoTrajectoryInfoPtr
 
using UpdateScenePosesFunc = std::function< void(const std::string &, const msgs::PosesStamped &)>
 Function signature for API that updates scene poses. More...
 
typedef std::shared_ptr< UserCmdManagerUserCmdManagerPtr
 
typedef std::shared_ptr< UserCmdUserCmdPtr
 
typedef boost::shared_ptr< WorldWorldPtr
 

Functions

WorldPtr create_world (const std::string &_name="")
 Create a world given a name. More...
 
bool fini ()
 Finalize transport by calling gazebo::transport::fini. More...
 
WorldPtr get_world (const std::string &_name="")
 Returns a pointer to a world by name. More...
 
uint32_t getUniqueId ()
 Get a unique ID. More...
 
bool has_world (const std::string &_name="")
 checks if the world with this name exists. More...
 
void init_world (WorldPtr _world) GAZEBO_DEPRECATED(11.0)
 Init world given a pointer to it. More...
 
void init_world (WorldPtr _world, UpdateScenePosesFunc _func)
 Init world given a pointer to it. More...
 
void init_worlds () GAZEBO_DEPRECATED(11.0)
 initialize multiple worlds stored in static variable gazebo::g_worlds More...
 
void init_worlds (UpdateScenePosesFunc _func)
 initialize multiple worlds stored in static variable gazebo::g_worlds More...
 
bool load ()
 Setup gazebo::SystemPlugin's and call gazebo::transport::init. More...
 
void load_world (WorldPtr _world, sdf::ElementPtr _sdf)
 Load world from sdf::Element pointer. More...
 
void load_worlds (sdf::ElementPtr _sdf)
 load multiple worlds from single sdf::Element pointer More...
 
void pause_world (WorldPtr _world, bool _pause)
 Pause world by calling World::SetPaused. More...
 
void pause_worlds (bool pause)
 pause multiple worlds stored in static variable gazebo::g_worlds More...
 
void remove_worlds ()
 remove multiple worlds stored in static variable gazebo::g_worlds More...
 
void run_world (WorldPtr _world, unsigned int _iterations=0)
 Run world by calling World::Run() given a pointer to it. More...
 
void run_worlds (unsigned int _iterations=0)
 Run multiple worlds stored in static variable gazebo::g_worlds. More...
 
void stop_world (WorldPtr _world)
 Stop world by calling World::Stop() given a pointer to it. More...
 
void stop_worlds ()
 stop multiple worlds stored in static variable gazebo::g_worlds More...
 
bool worlds_running ()
 Return true if any world is running. More...
 

Variables

static std::string EntityTypename []
 String names for the different entity types. More...
 

Detailed Description

namespace for physics

Physics forward declarations and type defines.

physics namespace

Typedef Documentation

◆ Actor_V

typedef std::vector<ActorPtr> Actor_V

◆ ActorPtr

typedef boost::shared_ptr<Actor> ActorPtr

◆ Base_V

typedef std::vector<BasePtr> Base_V

◆ BasePtr

typedef boost::shared_ptr<Base> BasePtr

◆ BoxShapePtr

typedef boost::shared_ptr<BoxShape> BoxShapePtr

◆ BulletCollisionPtr

typedef boost::shared_ptr<BulletCollision> BulletCollisionPtr

◆ BulletLinkPtr

typedef boost::shared_ptr<BulletLink> BulletLinkPtr

◆ BulletMotionStatePtr

typedef boost::shared_ptr<BulletMotionState> BulletMotionStatePtr

◆ BulletPhysicsPtr

typedef boost::shared_ptr<BulletPhysics> BulletPhysicsPtr

◆ BulletRayShapePtr

typedef boost::shared_ptr<BulletRayShape> BulletRayShapePtr

◆ BulletSurfaceParamsPtr

typedef boost::shared_ptr<BulletSurfaceParams> BulletSurfaceParamsPtr

◆ Collision_V

typedef std::vector<CollisionPtr> Collision_V

◆ CollisionPtr

typedef boost::shared_ptr<Collision> CollisionPtr

◆ ContactPtr

typedef boost::shared_ptr<Contact> ContactPtr

◆ CylinderShapePtr

typedef boost::shared_ptr<CylinderShape> CylinderShapePtr

◆ DARTBodyNodePropPtr

using DARTBodyNodePropPtr = std::shared_ptr<dart::dynamics::BodyNode::Properties>

◆ DARTCollisionPtr

typedef boost::shared_ptr<DARTCollision> DARTCollisionPtr

◆ DARTJointPropPtr

using DARTJointPropPtr = std::shared_ptr<dart::dynamics::Joint::Properties>

◆ DARTJointPtr

typedef boost::shared_ptr<DARTJoint> DARTJointPtr

◆ DARTLinkPtr

typedef boost::shared_ptr<DARTLink> DARTLinkPtr

◆ DARTModelPtr

typedef boost::shared_ptr<DARTModel> DARTModelPtr

◆ DARTPhysicsPtr

typedef boost::shared_ptr<DARTPhysics> DARTPhysicsPtr

◆ DARTRayShapePtr

typedef boost::shared_ptr<DARTRayShape> DARTRayShapePtr

◆ DARTSurfaceParamsPtr

typedef boost::shared_ptr<DARTSurfaceParams> DARTSurfaceParamsPtr

◆ EntityPtr

typedef boost::shared_ptr<Entity> EntityPtr

◆ FrictionPyramidPtr

typedef boost::shared_ptr<FrictionPyramid> FrictionPyramidPtr

◆ GripperPtr

typedef boost::shared_ptr<Gripper> GripperPtr

◆ HeightmapShapePtr

typedef boost::shared_ptr<HeightmapShape> HeightmapShapePtr

◆ InertialPtr

typedef boost::shared_ptr<Inertial> InertialPtr

◆ Joint_V

typedef std::vector<JointPtr> Joint_V

◆ JointController_V

typedef std::vector<JointControllerPtr> JointController_V

◆ JointControllerPtr

typedef boost::shared_ptr<JointController> JointControllerPtr

◆ JointPtr

typedef boost::shared_ptr<Joint> JointPtr

◆ JointState_M

typedef std::map<std::string, JointState> JointState_M

◆ Light_V

typedef std::vector<LightPtr> Light_V

◆ LightPtr

typedef boost::shared_ptr<Light> LightPtr

◆ LightState_M

typedef std::map<std::string, LightState> LightState_M

◆ Link_V

typedef std::vector<LinkPtr> Link_V

◆ LinkPtr

typedef boost::shared_ptr<Link> LinkPtr

◆ LinkState_M

typedef std::map<std::string, LinkState> LinkState_M

◆ MeshShapePtr

typedef boost::shared_ptr<MeshShape> MeshShapePtr

◆ Model_V

typedef std::vector<ModelPtr> Model_V

◆ ModelPtr

typedef boost::shared_ptr<Model> ModelPtr

◆ ModelState_M

typedef std::map<std::string, ModelState> ModelState_M

◆ MultiRayShapePtr

typedef boost::shared_ptr<MultiRayShape> MultiRayShapePtr

◆ PhysicsEnginePtr

typedef boost::shared_ptr<PhysicsEngine> PhysicsEnginePtr

◆ PlaneShapePtr

typedef boost::shared_ptr<PlaneShape> PlaneShapePtr

◆ PolylineShapePtr

typedef boost::shared_ptr<PolylineShape> PolylineShapePtr

◆ PresetManagerPtr

typedef boost::shared_ptr<PresetManager> PresetManagerPtr

◆ RayShapePtr

typedef boost::shared_ptr<RayShape> RayShapePtr

◆ RoadPtr

typedef boost::shared_ptr<Road> RoadPtr

◆ ShapePtr

typedef boost::shared_ptr<Shape> ShapePtr

◆ SphereShapePtr

typedef boost::shared_ptr<SphereShape> SphereShapePtr

◆ SurfaceParamsPtr

typedef boost::shared_ptr<SurfaceParams> SurfaceParamsPtr

◆ TrajectoryInfoPtr

typedef std::shared_ptr<TrajectoryInfo> TrajectoryInfoPtr

◆ UpdateScenePosesFunc

using UpdateScenePosesFunc = std::function<void(const std::string &, const msgs::PosesStamped &)>

Function signature for API that updates scene poses.

Parameters
[in]Stringname of scene update.
[in]Posesof objects in scene to update.

◆ UserCmdManagerPtr

typedef std::shared_ptr<UserCmdManager> UserCmdManagerPtr

◆ UserCmdPtr

typedef std::shared_ptr<UserCmd> UserCmdPtr

◆ WorldPtr

typedef boost::shared_ptr<World> WorldPtr