Classes | Typedefs | Functions | Variables
gazebo::physics Namespace Reference

namespace for physics More...

Classes

class  Actor
 Actor class enables GPU based mesh model / skeleton scriptable animation. 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  DARTBoxShapePrivate
 
class  DARTCollision
 Base class for all DART collisions. More...
 
class  DARTCollisionPrivate
 
class  DARTCylinderShape
 DART cylinder shape. More...
 
class  DARTCylinderShapePrivate
 
class  DARTFixedJoint
 A single axis hinge joint. More...
 
class  DARTHeightmapShape
 DART Height map collision. More...
 
class  DARTHeightmapShapePrivate
 
class  DARTHinge2Joint
 A two axis hinge joint. More...
 
class  DARTHingeJoint
 A single axis hinge joint. More...
 
class  DARTJoint
 DART joint interface. More...
 
class  DARTJointPrivate
 
class  DARTLink
 DART Link class. More...
 
class  DARTLinkPrivate
 
class  DARTMesh
 Triangle mesh collision helper class. More...
 
class  DARTMeshPrivate
 
class  DARTMeshShape
 Triangle mesh collision. More...
 
class  DARTMeshShapePrivate
 
class  DARTModel
 DART model class. More...
 
class  DARTModelPrivate
 
class  DARTMultiRayShape
 DART specific version of MultiRayShape. More...
 
class  DARTMultiRayShapePrivate
 
class  DARTPhysics
 DART physics engine. More...
 
class  DARTPhysicsPrivate
 
class  DARTPlaneShape
 An DART Plane shape. More...
 
class  DARTPlaneShapePrivate
 
class  DARTPolylineShape
 DART polyline shape. More...
 
class  DARTPolylineShapePrivate
 
class  DARTRayShape
 Ray collision. More...
 
class  DARTRayShapePrivate
 
class  DARTScrewJoint
 A screw joint. More...
 
class  DARTSliderJoint
 A slider joint. More...
 
class  DARTSphereShape
 A DART sphere shape. More...
 
class  DARTSphereShapePrivate
 
class  DARTSurfaceParams
 DART surface parameters. More...
 
class  DARTSurfaceParamsPrivate
 
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  JointControllerPrivate
 
class  JointState
 keeps track of state of a physics::Joint More...
 
class  JointWrench
 Wrench information from a joint. 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  ODEJointFeedback
 Data structure for contact feedbacks. 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  ODEPhysicsPrivate
 
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  PopulationPrivate
 Private data for the Population class. More...
 
class  Preset
 Representation of a preset physics profile. More...
 
class  PresetManager
 Class to manage preset physics profiles. More...
 
class  PresetManagerPrivate
 
class  PresetPrivate
 
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  World
 The world provides access to all other object within a simulated environment. More...
 
class  WorldPrivate
 Private data class for World. 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::vector< BasePtrBase_V
 
typedef boost::shared_ptr< BaseBasePtr
 
typedef boost::shared_ptr
< BoxShape
BoxShapePtr
 
typedef boost::shared_ptr
< BulletCollision
BulletCollisionPtr
 
typedef boost::shared_ptr
< BulletLink
BulletLinkPtr
 
typedef boost::shared_ptr
< BulletMotionState
BulletMotionStatePtr
 
typedef boost::shared_ptr
< BulletPhysics
BulletPhysicsPtr
 
typedef boost::shared_ptr
< BulletRayShape
BulletRayShapePtr
 
typedef boost::shared_ptr
< BulletSurfaceParams
BulletSurfaceParamsPtr
 
typedef std::vector< CollisionPtrCollision_V
 
typedef boost::shared_ptr
< Collision
CollisionPtr
 
typedef boost::shared_ptr
< Contact
ContactPtr
 
typedef boost::shared_ptr
< CylinderShape
CylinderShapePtr
 
typedef boost::shared_ptr
< DARTCollision
DARTCollisionPtr
 
typedef boost::shared_ptr
< DARTJoint
DARTJointPtr
 
typedef boost::shared_ptr
< DARTLink
DARTLinkPtr
 
typedef boost::shared_ptr
< DARTModel
DARTModelPtr
 
typedef boost::shared_ptr
< DARTPhysics
DARTPhysicsPtr
 
typedef boost::shared_ptr
< DARTRayShape
DARTRayShapePtr
 
typedef boost::shared_ptr
< DARTSurfaceParams
DARTSurfaceParamsPtr
 
typedef boost::shared_ptr< EntityEntityPtr
 
typedef boost::shared_ptr
< FrictionPyramid
FrictionPyramidPtr
 
typedef boost::shared_ptr
< Gripper
GripperPtr
 
typedef boost::shared_ptr
< HeightmapShape
HeightmapShapePtr
 
typedef boost::shared_ptr
< Inertial
InertialPtr
 
typedef std::vector< JointPtrJoint_V
 
typedef std::vector
< JointControllerPtr
JointController_V
 
typedef boost::shared_ptr
< JointController
JointControllerPtr
 
typedef boost::shared_ptr< JointJointPtr
 
typedef std::map< std::string,
JointState
JointState_M
 
typedef std::vector< LinkPtrLink_V
 
typedef boost::shared_ptr< LinkLinkPtr
 
typedef std::map< std::string,
LinkState
LinkState_M
 
typedef boost::shared_ptr
< MeshShape
MeshShapePtr
 
typedef std::vector< ModelPtrModel_V
 
typedef boost::shared_ptr< ModelModelPtr
 
typedef std::map< std::string,
ModelState
ModelState_M
 
typedef boost::shared_ptr
< MultiRayShape
MultiRayShapePtr
 
typedef boost::shared_ptr
< ODECollision
ODECollisionPtr
 
typedef boost::shared_ptr
< ODEJoint
ODEJointPtr
 
typedef boost::shared_ptr
< ODELink
ODELinkPtr
 
typedef boost::shared_ptr
< ODEPhysics
ODEPhysicsPtr
 
typedef boost::shared_ptr
< ODERayShape
ODERayShapePtr
 
typedef boost::shared_ptr
< ODESurfaceParams
ODESurfaceParamsPtr
 
typedef boost::shared_ptr
< PhysicsEngine
PhysicsEnginePtr
 
typedef PhysicsEnginePtr(* PhysicsFactoryFn )(WorldPtr world)
 
typedef boost::shared_ptr
< PlaneShape
PlaneShapePtr
 
typedef boost::shared_ptr
< PolylineShape
PolylineShapePtr
 
typedef boost::shared_ptr
< PresetManager
PresetManagerPtr
 
typedef boost::shared_ptr
< RayShape
RayShapePtr
 
typedef boost::shared_ptr< RoadRoadPtr
 
typedef boost::shared_ptr< ShapeShapePtr
 
typedef boost::shared_ptr
< SimbodyCollision
SimbodyCollisionPtr
 
typedef boost::shared_ptr
< SimbodyLink
SimbodyLinkPtr
 
typedef boost::shared_ptr
< SimbodyModel
SimbodyModelPtr
 
typedef boost::shared_ptr
< SimbodyPhysics
SimbodyPhysicsPtr
 
typedef boost::shared_ptr
< SimbodyRayShape
SimbodyRayShapePtr
 
typedef boost::shared_ptr
< SphereShape
SphereShapePtr
 
typedef boost::shared_ptr
< SurfaceParams
SurfaceParamsPtr
 
typedef boost::shared_ptr< WorldWorldPtr
 

Functions

GZ_PHYSICS_VISIBLE WorldPtr create_world (const std::string &_name="")
 Create a world given a name. More...
 
GZ_PHYSICS_VISIBLE bool fini ()
 Finalize transport by calling gazebo::transport::fini. More...
 
GZ_PHYSICS_VISIBLE WorldPtr get_world (const std::string &_name="")
 Returns a pointer to a world by name. More...
 
GZ_PHYSICS_VISIBLE uint32_t getUniqueId ()
 Get a unique ID. More...
 
GZ_PHYSICS_VISIBLE void init_world (WorldPtr _world)
 Init world given a pointer to it. More...
 
GZ_PHYSICS_VISIBLE void init_worlds ()
 initialize multiple worlds stored in static variable gazebo::g_worlds More...
 
GZ_PHYSICS_VISIBLE bool load ()
 Setup gazebo::SystemPlugin's and call gazebo::transport::init. More...
 
GZ_PHYSICS_VISIBLE void load_world (WorldPtr _world, sdf::ElementPtr _sdf)
 Load world from sdf::Element pointer. More...
 
GZ_PHYSICS_VISIBLE void load_worlds (sdf::ElementPtr _sdf)
 load multiple worlds from single sdf::Element pointer More...
 
GZ_PHYSICS_VISIBLE void pause_world (WorldPtr _world, bool _pause)
 Pause world by calling World::SetPaused. More...
 
GZ_PHYSICS_VISIBLE void pause_worlds (bool pause)
 pause multiple worlds stored in static variable gazebo::g_worlds More...
 
GZ_PHYSICS_VISIBLE void remove_worlds ()
 remove multiple worlds stored in static variable gazebo::g_worlds More...
 
GZ_PHYSICS_VISIBLE void run_world (WorldPtr _world, unsigned int _iterations=0)
 Run world by calling World::Run() given a pointer to it. More...
 
GZ_PHYSICS_VISIBLE void run_worlds (unsigned int _iterations=0)
 Run multiple worlds stored in static variable gazebo::g_worlds. More...
 
GZ_PHYSICS_VISIBLE void stop_world (WorldPtr _world)
 Stop world by calling World::Stop() given a pointer to it. More...
 
GZ_PHYSICS_VISIBLE void stop_worlds ()
 stop multiple worlds stored in static variable gazebo::g_worlds More...
 
GZ_PHYSICS_VISIBLE 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

typedef std::vector<ActorPtr> gazebo::physics::Actor_V
typedef boost::shared_ptr<Actor> gazebo::physics::ActorPtr
typedef std::vector<BasePtr> gazebo::physics::Base_V
typedef boost::shared_ptr<Base> gazebo::physics::BasePtr
typedef boost::shared_ptr<BoxShape> gazebo::physics::BoxShapePtr
typedef boost::shared_ptr<BulletLink> gazebo::physics::BulletLinkPtr
typedef boost::shared_ptr<Collision> gazebo::physics::CollisionPtr
typedef boost::shared_ptr<Contact> gazebo::physics::ContactPtr
typedef boost::shared_ptr<DARTJoint> gazebo::physics::DARTJointPtr
typedef boost::shared_ptr<DARTLink> gazebo::physics::DARTLinkPtr
typedef boost::shared_ptr<DARTModel> gazebo::physics::DARTModelPtr
typedef boost::shared_ptr<DARTPhysics> gazebo::physics::DARTPhysicsPtr
typedef boost::shared_ptr<DARTRayShape> gazebo::physics::DARTRayShapePtr
typedef boost::shared_ptr<Entity> gazebo::physics::EntityPtr
typedef boost::shared_ptr<Gripper> gazebo::physics::GripperPtr
typedef boost::shared_ptr<Inertial> gazebo::physics::InertialPtr
typedef std::vector<JointPtr> gazebo::physics::Joint_V
typedef boost::shared_ptr<Joint> gazebo::physics::JointPtr
typedef std::map<std::string, JointState> gazebo::physics::JointState_M
typedef std::vector<LinkPtr> gazebo::physics::Link_V
typedef boost::shared_ptr<Link> gazebo::physics::LinkPtr
typedef std::map<std::string, LinkState> gazebo::physics::LinkState_M
typedef boost::shared_ptr<MeshShape> gazebo::physics::MeshShapePtr
typedef std::vector<ModelPtr> gazebo::physics::Model_V
typedef boost::shared_ptr<Model> gazebo::physics::ModelPtr
typedef std::map<std::string, ModelState> gazebo::physics::ModelState_M
typedef boost::shared_ptr<ODECollision> gazebo::physics::ODECollisionPtr
typedef boost::shared_ptr<ODEJoint> gazebo::physics::ODEJointPtr
typedef boost::shared_ptr<ODELink> gazebo::physics::ODELinkPtr
typedef boost::shared_ptr<ODEPhysics> gazebo::physics::ODEPhysicsPtr
typedef boost::shared_ptr<ODERayShape> gazebo::physics::ODERayShapePtr
typedef boost::shared_ptr<PlaneShape> gazebo::physics::PlaneShapePtr
typedef boost::shared_ptr<RayShape> gazebo::physics::RayShapePtr
typedef boost::shared_ptr<Road> gazebo::physics::RoadPtr
typedef boost::shared_ptr<Shape> gazebo::physics::ShapePtr
typedef boost::shared_ptr<SimbodyLink> gazebo::physics::SimbodyLinkPtr
typedef boost::shared_ptr<SimbodyModel> gazebo::physics::SimbodyModelPtr
typedef boost::shared_ptr<SphereShape> gazebo::physics::SphereShapePtr
typedef boost::shared_ptr<World> gazebo::physics::WorldPtr