All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
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  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  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  BulletRaySensor
 An Bullet Ray sensor. 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  BulletTrimeshShape
 Triangle mesh collision. 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  ContactFeedback
 data structure for contact feedbacks More...
 
class  CylinderShape
 Cylinder collision. More...
 
class  Entity
 Base class for all physics objects in Gazebo. 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  JointFeedback
 Feedback information from a joint. More...
 
class  JointState
 keeps track of state of a physics::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  Logger
 Handles logging of data to disk. More...
 
class  Logplay
 Open and playback log files that were recorded using Logger. More...
 
class  MapShape
 Creates box extrusions based on an image. 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  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  ODEMultiRayShape
 ODE specific version of MultiRayShape. More...
 
class  ODEPhysics
 ODE physics engine. More...
 
class  ODEPlaneShape
 An ODE Plane 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
 Surface params. More...
 
class  ODETrimeshShape
 Triangle mesh collision. 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  RayShape
 Base class for Ray collision geometry. More...
 
class  Road
 for building a Road from SDF More...
 
class  ScrewJoint
 A screw joint. More...
 
class  Shape
 Base class for all shapes. More...
 
class  SliderJoint
 A slider joint. More...
 
class  SphereShape
 Sphere collision. More...
 
class  State
 State of an entity. More...
 
class  SurfaceParams
 SurfaceParams defines various Surface contact parameters. More...
 
struct  TrajectoryInfo
 
class  TrimeshShape
 Triangle mesh collision shape. More...
 
class  UniversalJoint
 A universal joint. 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 ActorActorPtr
 
typedef std::vector< BasePtrBase_V
 
typedef BaseBasePtr
 
typedef BoxShapeBoxShapePtr
 
typedef BulletCollisionBulletCollisionPtr
 
typedef BulletLinkBulletLinkPtr
 
typedef BulletPhysicsBulletPhysicsPtr
 
typedef BulletRayShapeBulletRayShapePtr
 
typedef std::vector< CollisionPtrCollision_V
 
typedef CollisionCollisionPtr
 
typedef ContactContactPtr
 
typedef CylinderShapeCylinderShapePtr
 
typedef EntityEntityPtr
 
typedef HeightmapShapeHeightmapShapePtr
 
typedef InertialInertialPtr
 
typedef std::vector< JointPtrJoint_V
 
typedef JointJointPtr
 
typedef std::vector< LinkPtrLink_V
 
typedef LinkLinkPtr
 
typedef MeshShape * MeshShapePtr
 
typedef std::vector< ModelPtrModel_V
 
typedef ModelModelPtr
 
typedef MultiRayShapeMultiRayShapePtr
 
typedef ODECollisionODECollisionPtr
 
typedef ODELinkODELinkPtr
 
typedef ODEPhysicsODEPhysicsPtr
 
typedef ODERayShapeODERayShapePtr
 
typedef ODESurfaceParamsODESurfaceParamsPtr
 
typedef PhysicsEnginePhysicsEnginePtr
 
typedef PhysicsEnginePtr(* PhysicsFactoryFn )(WorldPtr world)
 
typedef RayShapeRayShapePtr
 
typedef RoadRoadPtr
 
typedef ShapeShapePtr
 
typedef SphereShapeSphereShapePtr
 
typedef SurfaceParamsSurfaceParamsPtr
 
typedef WorldWorldPtr
 

Functions

WorldPtr create_world (const std::string &_name="")
 Create a world given a name.
 
bool fini ()
 Finalize transport by calling gazebo::transport::fini.
 
WorldPtr get_world (const std::string &_name="")
 Returns a pointer to a world by name.
 
void init_world (WorldPtr _world)
 Init world given a pointer to it.
 
void init_worlds ()
 initialize multiple worlds stored in static variable gazebo::g_worlds
 
bool load ()
 Setup gazebo::SystemPlugin's and call gazebo::transport::init.
 
void load_world (WorldPtr _world, sdf::ElementPtr _sdf)
 Load world from sdf::Element pointer.
 
void load_worlds (sdf::ElementPtr _sdf)
 load multiple worlds from single sdf::Element pointer
 
void pause_world (WorldPtr _world, bool _pause)
 Pause world by calling World::SetPaused.
 
void pause_worlds (bool pause)
 pause multiple worlds stored in static variable gazebo::g_worlds
 
void remove_worlds ()
 remove multiple worlds stored in static variable gazebo::g_worlds
 
void run_world (WorldPtr _world)
 Run world by calling World::Run() given a pointer to it.
 
void run_worlds ()
 run multiple worlds stored in static variable gazebo::g_worlds
 
void stop_world (WorldPtr _world)
 Stop world by calling World::Stop() given a pointer to it.
 
void stop_worlds ()
 stop multiple worlds stored in static variable gazebo::g_worlds
 

Variables

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

Detailed Description

namespace for physics

Physics forward declarations and type defines.

physics namespace

Typedef Documentation

typedef std::vector<ActorPtr> gazebo::physics::Actor_V
typedef std::vector<BasePtr> gazebo::physics::Base_V
typedef std::vector<JointPtr> gazebo::physics::Joint_V
typedef std::vector<LinkPtr> gazebo::physics::Link_V
typedef MeshShape* gazebo::physics::MeshShapePtr
typedef std::vector<ModelPtr> gazebo::physics::Model_V