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 | 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 | 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 | 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 | 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< ActorPtr > | Actor_V | 
| typedef Actor * | ActorPtr | 
| typedef std::vector< BasePtr > | Base_V | 
| typedef Base * | BasePtr | 
| typedef BoxShape * | BoxShapePtr | 
| typedef std::vector< CollisionPtr > | Collision_V | 
| typedef Collision * | CollisionPtr | 
| typedef Contact * | ContactPtr | 
| typedef CylinderShape * | CylinderShapePtr | 
| typedef Entity * | EntityPtr | 
| typedef HeightmapShape * | HeightmapShapePtr | 
| typedef Inertial * | InertialPtr | 
| typedef std::vector< JointPtr > | Joint_V | 
| typedef Joint * | JointPtr | 
| typedef std::vector< LinkPtr > | Link_V | 
| typedef Link * | LinkPtr | 
| typedef MeshShape * | MeshShapePtr | 
| typedef std::vector< ModelPtr > | Model_V | 
| typedef Model * | ModelPtr | 
| typedef MultiRayShape * | MultiRayShapePtr | 
| typedef PhysicsEngine * | PhysicsEnginePtr | 
| typedef PhysicsEnginePtr(* | PhysicsFactoryFn )(WorldPtr world) | 
| typedef RayShape * | RayShapePtr | 
| typedef Road * | RoadPtr | 
| typedef Shape * | ShapePtr | 
| typedef SphereShape * | SphereShapePtr | 
| typedef SurfaceParams * | SurfaceParamsPtr | 
| typedef World * | WorldPtr | 
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.   | |
namespace for physics
Physics forward declarations and type defines.
physics namespace
| typedef std::vector<ActorPtr> gazebo::physics::Actor_V | 
| typedef Actor* gazebo::physics::ActorPtr | 
| typedef std::vector<BasePtr> gazebo::physics::Base_V | 
| typedef Base* gazebo::physics::BasePtr | 
| typedef BoxShape* gazebo::physics::BoxShapePtr | 
| typedef std::vector<CollisionPtr> gazebo::physics::Collision_V | 
| typedef Collision* gazebo::physics::CollisionPtr | 
| typedef Contact* gazebo::physics::ContactPtr | 
| typedef Entity* gazebo::physics::EntityPtr | 
| typedef Inertial* gazebo::physics::InertialPtr | 
| typedef std::vector<JointPtr> gazebo::physics::Joint_V | 
| typedef Joint* gazebo::physics::JointPtr | 
| typedef std::vector<LinkPtr> gazebo::physics::Link_V | 
| typedef Link* gazebo::physics::LinkPtr | 
| typedef MeshShape* gazebo::physics::MeshShapePtr | 
| typedef std::vector<ModelPtr> gazebo::physics::Model_V | 
| typedef Model* gazebo::physics::ModelPtr | 
| typedef RayShape* gazebo::physics::RayShapePtr | 
| typedef Road* gazebo::physics::RoadPtr | 
| typedef Shape* gazebo::physics::ShapePtr | 
| typedef World* gazebo::physics::WorldPtr |