All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Files | Namespaces | Classes | Macros | Typedefs | Functions | Variables
Classes for physics and dynamics

Files

file  PhysicsTypes.hh
 default namespace for gazebo

Namespaces

namespace  gazebo::physics
 namespace for physics

Classes

class  gazebo::physics::Actor
 Actor class enables GPU based mesh model / skeleton scriptable animation. More...
class  gazebo::physics::BallJoint< T >
 Base class for a ball joint. More...
class  gazebo::physics::Base
 Base class for most physics classes. More...
class  gazebo::physics::BoxShape
 Box geometry primitive. More...
class  gazebo::physics::Collision
 Base class for all collision entities. More...
class  gazebo::physics::CollisionState
 Store state information of a physics::Collision object. More...
class  gazebo::physics::Contact
 A contact between two collisions. More...
class  gazebo::physics::ContactManager
 Aggregates all the contact information generated by the collision detection engine. More...
class  gazebo::physics::CylinderShape
 Cylinder collision. More...
class  gazebo::physics::Entity
 Base class for all physics objects in Gazebo. More...
class  gazebo::physics::Gripper
 A gripper abstraction. More...
class  gazebo::physics::HeightmapShape
 HeightmapShape collision shape builds a heightmap from an image. More...
class  gazebo::physics::Hinge2Joint< T >
 A two axis hinge joint. More...
class  gazebo::physics::HingeJoint< T >
 A single axis hinge joint. More...
class  gazebo::physics::Inertial
 A class for inertial information about a link. More...
class  gazebo::physics::Joint
 Base class for all joints. More...
class  gazebo::physics::JointController
 A class for manipulating physics::Joint. More...
class  gazebo::physics::JointState
 keeps track of state of a physics::Joint More...
class  gazebo::physics::JointWrench
 Wrench information from a joint. More...
class  gazebo::physics::Link
 Link class defines a rigid body entity, containing information on inertia, visual and collision properties of a rigid body. More...
class  gazebo::physics::LinkState
 Store state information of a physics::Link object. More...
class  Logplay
 Open and playback log files that were recorded using LogRecord. More...
class  gazebo::util::LogPlay
class  gazebo::physics::MeshShape
 Triangle mesh collision shape. More...
class  gazebo::physics::Model
 A model is a collection of links, joints, and plugins. More...
class  gazebo::physics::ModelState
 Store state information of a physics::Model object. More...
class  gazebo::physics::MultiRayShape
 Laser collision contains a set of ray-collisions, structured to simulate a laser range scanner. More...
class  gazebo::physics::PhysicsEngine
 Base class for a physics engine. More...
class  gazebo::physics::PhysicsFactory
 The physics factory instantiates different physics engines. More...
class  gazebo::physics::PlaneShape
 Collision for an infinite plane. More...
class  gazebo::physics::RayShape
 Base class for Ray collision geometry. More...
class  gazebo::physics::Road
 for building a Road from SDF More...
class  gazebo::physics::ScrewJoint< T >
 A screw joint, which has both prismatic and rotational DOFs. More...
class  gazebo::physics::Shape
 Base class for all shapes. More...
class  gazebo::physics::SliderJoint< T >
 A slider joint. More...
class  gazebo::physics::SphereShape
 Sphere collision shape. More...
class  gazebo::physics::State
 State of an entity. More...
class  gazebo::physics::SurfaceParams
 SurfaceParams defines various Surface contact parameters. More...
class  gazebo::physics::UniversalJoint< T >
 A universal joint. More...
class  gazebo::physics::World
 The world provides access to all other object within a simulated environment. More...
class  gazebo::physics::WorldState
 Store state information of a physics::World object. More...

Macros

#define GZ_REGISTER_PHYSICS_ENGINE(name, classname)
 Static physics registration macro.

Typedefs

typedef PhysicsEnginePtr(* gazebo::physics::PhysicsFactoryFn )(WorldPtr world)

Functions

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

Variables

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

Detailed Description

Macro Definition Documentation

#define GZ_REGISTER_PHYSICS_ENGINE (   name,
  classname 
)
Value:
PhysicsEnginePtr New##classname(WorldPtr _world) \
{ \
return PhysicsEnginePtr(new gazebo::physics::classname(_world)); \
} \
void Register##classname() \
{\
PhysicsFactory::RegisterPhysicsEngine(name, New##classname);\
}

Static physics registration macro.

Use this macro to register physics engine with the server.

Parameters
[in]namePhysics type name, as it appears in the world file.
[in]classnameC++ class name for the physics engine.

Typedef Documentation

typedef PhysicsEnginePtr(* gazebo::physics::PhysicsFactoryFn)(WorldPtr world)

Function Documentation

WorldPtr gazebo::physics::create_world ( const std::string &  _name = "")

Create a world given a name.

Parameters
[in]_nameName of the world to create.
Returns
Pointer to the new world.
bool gazebo::physics::fini ( )

Finalize transport by calling gazebo::transport::fini.

WorldPtr gazebo::physics::get_world ( const std::string &  _name = "")

Returns a pointer to a world by name.

Parameters
[in]_nameName of the world to get.
Returns
Pointer to the world.

Referenced by Joint_TEST::SpawnJoint().

void gazebo::physics::init_world ( WorldPtr  _world)

Init world given a pointer to it.

Parameters
[in]_worldWorld to initialize.
void gazebo::physics::init_worlds ( )

initialize multiple worlds stored in static variable gazebo::g_worlds

bool gazebo::physics::load ( )
void gazebo::physics::load_world ( WorldPtr  _world,
sdf::ElementPtr  _sdf 
)

Load world from sdf::Element pointer.

Parameters
[in]_worldPointer to a world.
[in]_sdfSDF values to load from.
void gazebo::physics::load_worlds ( sdf::ElementPtr  _sdf)

load multiple worlds from single sdf::Element pointer

Parameters
[in]_sdfSDF values used to create worlds.
void gazebo::physics::pause_world ( WorldPtr  _world,
bool  _pause 
)

Pause world by calling World::SetPaused.

Parameters
[in]_worldWorld to pause or unpause.
[in]_pauseTrue to pause, False to unpause.
void gazebo::physics::pause_worlds ( bool  pause)

pause multiple worlds stored in static variable gazebo::g_worlds

Parameters
[in]_pauseTrue to pause, False to unpause.
void gazebo::physics::remove_worlds ( )

remove multiple worlds stored in static variable gazebo::g_worlds

void gazebo::physics::run_world ( WorldPtr  _world,
unsigned int  _iterations = 0 
)

Run world by calling World::Run() given a pointer to it.

Parameters
[in]_worldWorld to run.
[in]_iterationsNumber of iterations for each world to take. Zero indicates that each world should continue forever.
void gazebo::physics::run_worlds ( unsigned int  _iterations = 0)

Run multiple worlds stored in static variable gazebo::g_worlds.

Parameters
[in]_iterationsNumber of iterations for each world to take. Zero indicates that each world should continue forever.
void gazebo::physics::stop_world ( WorldPtr  _world)

Stop world by calling World::Stop() given a pointer to it.

Parameters
[in]_worldWorld to stop.
void gazebo::physics::stop_worlds ( )

stop multiple worlds stored in static variable gazebo::g_worlds

bool gazebo::physics::worlds_running ( )

Return true if any world is running.

Returns
True if any world is running.

Variable Documentation

std::string gazebo::physics::EntityTypename[]
static
Initial value:
{
"common",
"entity",
"model",
"actor",
"link",
"collision",
"light",
"visual",
"joint",
"ball",
"hinge2",
"hinge",
"slider",
"universal",
"shape",
"box",
"cylinder",
"heightmap",
"map",
"multiray",
"ray",
"plane",
"sphere",
"trimesh"
}

String names for the different entity types.