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  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  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  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  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, 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  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  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  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...
 
struct  TrajectoryInfo
 
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 boost::shared_ptr< ActorActorPtr
 
typedef std::vector< BasePtrBase_V
 
typedef boost::shared_ptr< BaseBasePtr
 
typedef boost::shared_ptr
< BoxShape
BoxShapePtr
 
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< EntityEntityPtr
 
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
< PhysicsEngine
PhysicsEnginePtr
 
typedef PhysicsEnginePtr(* PhysicsFactoryFn )(WorldPtr world)
 
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

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...
 
void init_world (WorldPtr _world)
 Init world given a pointer to it. More...
 
void init_worlds ()
 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

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<Collision> gazebo::physics::CollisionPtr
typedef boost::shared_ptr<Contact> gazebo::physics::ContactPtr
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<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