default namespace for gazebo More...
#include <vector>#include <map>#include <string>#include <boost/shared_ptr.hpp>

Go to the source code of this file.
| Namespaces | |
| namespace | gazebo | 
| Forward declarations for the common classes. | |
| namespace | gazebo::physics | 
| namespace for physics | |
| Macros | |
| #define | GZ_ALL_COLLIDE 0x0FFFFFFF | 
| Default collision bitmask.  More... | |
| #define | GZ_FIXED_COLLIDE 0x00000001 | 
| Collision object will collide only with fixed objects.  More... | |
| #define | GZ_GHOST_COLLIDE 0x10000000 | 
| Collides with everything else but other ghost.  More... | |
| #define | GZ_NONE_COLLIDE 0x00000000 | 
| Collision object will collide with nothing.  More... | |
| #define | GZ_SENSOR_COLLIDE 0x00000002 | 
| Collision object will collide only with sensors.  More... | |
| Typedefs | |
| 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 std::vector< CollisionPtr > | gazebo::physics::Collision_V | 
| typedef boost::shared_ptr < Collision > | gazebo::physics::CollisionPtr | 
| typedef boost::shared_ptr < Contact > | gazebo::physics::ContactPtr | 
| typedef boost::shared_ptr < CylinderShape > | gazebo::physics::CylinderShapePtr | 
| typedef boost::shared_ptr< Entity > | gazebo::physics::EntityPtr | 
| typedef boost::shared_ptr < Gripper > | gazebo::physics::GripperPtr | 
| typedef boost::shared_ptr < HeightmapShape > | gazebo::physics::HeightmapShapePtr | 
| typedef boost::shared_ptr < Inertial > | gazebo::physics::InertialPtr | 
| typedef std::vector< JointPtr > | gazebo::physics::Joint_V | 
| typedef std::vector < JointControllerPtr > | gazebo::physics::JointController_V | 
| typedef boost::shared_ptr < JointController > | gazebo::physics::JointControllerPtr | 
| 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 < MultiRayShape > | gazebo::physics::MultiRayShapePtr | 
| typedef boost::shared_ptr < PhysicsEngine > | gazebo::physics::PhysicsEnginePtr | 
| 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 < SphereShape > | gazebo::physics::SphereShapePtr | 
| typedef boost::shared_ptr < SurfaceParams > | gazebo::physics::SurfaceParamsPtr | 
| typedef boost::shared_ptr< World > | gazebo::physics::WorldPtr | 
default namespace for gazebo
| #define GZ_ALL_COLLIDE 0x0FFFFFFF | 
Default collision bitmask.
Collision objects will collide with everything.
| #define GZ_FIXED_COLLIDE 0x00000001 | 
Collision object will collide only with fixed objects.
| #define GZ_GHOST_COLLIDE 0x10000000 | 
Collides with everything else but other ghost.
| #define GZ_NONE_COLLIDE 0x00000000 | 
Collision object will collide with nothing.
| #define GZ_SENSOR_COLLIDE 0x00000002 | 
Collision object will collide only with sensors.