default namespace for gazebo More...
#include <map>#include <memory>#include <string>#include <vector>#include <boost/shared_ptr.hpp>#include "gazebo/msgs/poses_stamped.pb.h"#include "gazebo/util/system.hh"Go to the source code of this file.
Namespaces | |
| gazebo | |
| Forward declarations for the common classes. | |
| 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 > | Actor_V |
| typedef boost::shared_ptr< Actor > | ActorPtr |
| typedef std::vector< BasePtr > | Base_V |
| typedef boost::shared_ptr< Base > | BasePtr |
| typedef boost::shared_ptr< BoxShape > | BoxShapePtr |
| typedef std::vector< CollisionPtr > | Collision_V |
| typedef boost::shared_ptr< Collision > | CollisionPtr |
| typedef boost::shared_ptr< Contact > | ContactPtr |
| typedef boost::shared_ptr< CylinderShape > | CylinderShapePtr |
| typedef boost::shared_ptr< Entity > | EntityPtr |
| typedef boost::shared_ptr< FrictionPyramid > | FrictionPyramidPtr |
| typedef boost::shared_ptr< Gripper > | GripperPtr |
| typedef boost::shared_ptr< HeightmapShape > | HeightmapShapePtr |
| typedef boost::shared_ptr< Inertial > | InertialPtr |
| typedef std::vector< JointPtr > | Joint_V |
| typedef std::vector< JointControllerPtr > | JointController_V |
| typedef boost::shared_ptr< JointController > | JointControllerPtr |
| typedef boost::shared_ptr< Joint > | JointPtr |
| typedef std::map< std::string, JointState > | JointState_M |
| typedef std::vector< LightPtr > | Light_V |
| typedef boost::shared_ptr< Light > | LightPtr |
| typedef std::map< std::string, LightState > | LightState_M |
| typedef std::vector< LinkPtr > | Link_V |
| typedef boost::shared_ptr< Link > | LinkPtr |
| typedef std::map< std::string, LinkState > | LinkState_M |
| typedef boost::shared_ptr< MeshShape > | MeshShapePtr |
| typedef std::vector< ModelPtr > | Model_V |
| typedef boost::shared_ptr< Model > | ModelPtr |
| typedef std::map< std::string, ModelState > | ModelState_M |
| typedef boost::shared_ptr< MultiRayShape > | MultiRayShapePtr |
| typedef boost::shared_ptr< PhysicsEngine > | PhysicsEnginePtr |
| typedef boost::shared_ptr< PlaneShape > | PlaneShapePtr |
| typedef boost::shared_ptr< PolylineShape > | PolylineShapePtr |
| typedef boost::shared_ptr< PresetManager > | PresetManagerPtr |
| typedef boost::shared_ptr< RayShape > | RayShapePtr |
| typedef boost::shared_ptr< Road > | RoadPtr |
| typedef boost::shared_ptr< Shape > | ShapePtr |
| typedef boost::shared_ptr< SphereShape > | SphereShapePtr |
| typedef boost::shared_ptr< SurfaceParams > | SurfaceParamsPtr |
| typedef std::shared_ptr< TrajectoryInfo > | TrajectoryInfoPtr |
| using | UpdateScenePosesFunc = std::function< void(const std::string &, const msgs::PosesStamped &)> |
| Function signature for API that updates scene poses. More... | |
| typedef std::shared_ptr< UserCmdManager > | UserCmdManagerPtr |
| typedef std::shared_ptr< UserCmd > | UserCmdPtr |
| typedef boost::shared_ptr< World > | 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.