17 #ifndef _PHYSICSENGINE_HH_
18 #define _PHYSICSENGINE_HH_
20 #include <boost/thread/recursive_mutex.hpp>
51 public:
virtual void Load(sdf::ElementPtr _sdf);
54 public:
virtual void Init() = 0;
57 public:
virtual void Fini();
63 public:
virtual void InitForThread() = 0;
66 public:
virtual void UpdateCollision() = 0;
70 public:
virtual std::string GetType()
const = 0;
74 public:
virtual void SetSeed(uint32_t _seed) = 0;
78 public:
double GetUpdatePeriod();
82 public:
double GetTargetRealTimeFactor()
const;
86 public:
double GetRealTimeUpdateRate()
const;
90 public:
double GetMaxStepSize()
const;
94 public:
void SetTargetRealTimeFactor(
double _factor);
98 public:
void SetRealTimeUpdateRate(
double _rate);
102 public:
void SetMaxStepSize(
double _stepSize);
119 const std::string &_shapeType,
LinkPtr _link) = 0;
124 public:
CollisionPtr CreateCollision(
const std::string &_shapeType,
125 const std::string &_linkName);
130 public:
virtual ShapePtr CreateShape(
const std::string &_shapeType,
136 public:
virtual JointPtr CreateJoint(
const std::string &_type,
145 public:
virtual void SetGravity(
150 public:
virtual ignition::math::Vector3d MagneticField()
const;
170 public:
virtual void SetAutoDisableFlag(
bool _autoDisable);
190 public:
virtual void SetMaxContacts(
unsigned int _maxContacts);
261 public:
virtual bool SetParam(
const std::string &_key,
262 const boost::any &_value);
268 public:
virtual boost::any GetParam(
const std::string &_key)
const;
275 public:
virtual bool GetParam(
const std::string &_key,
276 boost::any &_value)
const;
279 public:
virtual void DebugPrint()
const = 0;
288 {
return this->physicsUpdateMutex;}
292 public: sdf::ElementPtr GetSDF()
const;
296 protected:
virtual void OnRequest(ConstRequestPtr &_msg);
300 protected:
virtual void OnPhysicsMsg(ConstPhysicsPtr &_msg);
306 protected: sdf::ElementPtr
sdf;
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:68
double realTimeUpdateRate
Real time update rate.
Definition: PhysicsEngine.hh:328
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:84
#define GZ_PHYSICS_VISIBLE
Definition: system.hh:318
double targetRealTimeFactor
Target real time factor.
Definition: PhysicsEngine.hh:331
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:39
virtual void UpdatePhysics()
Update the physics engine.
Definition: PhysicsEngine.hh:105
boost::shared_ptr< Shape > ShapePtr
Definition: PhysicsTypes.hh:116
boost::shared_ptr< Subscriber > SubscriberPtr
Definition: TransportTypes.hh:53
Base class for a physics engine.
Definition: PhysicsEngine.hh:40
virtual bool GetAutoDisableFlag()
: Remove this function, and replace it with a more generic property map
Definition: PhysicsEngine.hh:208
Forward declarations for transport.
virtual double GetWorldERP() GAZEBO_DEPRECATED(6.0)
: Remove this function, and replace it with a more generic property map
Definition: PhysicsEngine.hh:202
#define GAZEBO_DEPRECATED(version)
Definition: CommonTypes.hh:47
WorldPtr world
Pointer to the world.
Definition: PhysicsEngine.hh:303
virtual double GetWorldCFM() GAZEBO_DEPRECATED(6.0)
: Remove this function, and replace it with a more generic property map
Definition: PhysicsEngine.hh:196
sdf::ElementPtr sdf
Our SDF values.
Definition: PhysicsEngine.hh:306
boost::recursive_mutex * physicsUpdateMutex
Mutex to protect the update cycle.
Definition: PhysicsEngine.hh:321
default namespace for gazebo
boost::shared_ptr< Collision > CollisionPtr
Definition: PhysicsTypes.hh:96
transport::SubscriberPtr physicsSub
Subscribe to the physics topic.
Definition: PhysicsEngine.hh:315
virtual void SetContactMaxCorrectingVel(double) GAZEBO_DEPRECATED(6.0)
: Remove this function, and replace it with a more generic property map
Definition: PhysicsEngine.hh:176
virtual void SetContactSurfaceLayer(double) GAZEBO_DEPRECATED(6.0)
: Remove this function, and replace it with a more generic property map
Definition: PhysicsEngine.hh:183
virtual double GetContactMaxCorrectingVel() GAZEBO_DEPRECATED(6.0)
: Remove this function, and replace it with a more generic property map.
Definition: PhysicsEngine.hh:214
virtual void Reset()
Rest the physics engine.
Definition: PhysicsEngine.hh:60
transport::SubscriberPtr requestSub
Subscribe to the request topic.
Definition: PhysicsEngine.hh:318
virtual void SetWorldCFM(double) GAZEBO_DEPRECATED(6.0)
: Remove this function, and replace it with a more generic property map
Definition: PhysicsEngine.hh:156
boost::shared_ptr< World > WorldPtr
Definition: PhysicsTypes.hh:80
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:100
boost::shared_ptr< Node > NodePtr
Definition: TransportTypes.hh:57
boost::recursive_mutex * GetPhysicsUpdateMutex() const
returns a pointer to the PhysicsEngine::physicsUpdateMutex.
Definition: PhysicsEngine.hh:287
virtual double GetContactSurfaceLayer() GAZEBO_DEPRECATED(6.0)
: Remove this function, and replace it with a more generic property map.
Definition: PhysicsEngine.hh:221
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
virtual unsigned int GetMaxContacts()
: Remove this function, and replace it with a more generic property map.
Definition: PhysicsEngine.hh:228
virtual void SetWorldERP(double) GAZEBO_DEPRECATED(6.0)
: Remove this function, and replace it with a more generic property map
Definition: PhysicsEngine.hh:163
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:49
transport::PublisherPtr responsePub
Response publisher.
Definition: PhysicsEngine.hh:312
double maxStepSize
Real time update rate.
Definition: PhysicsEngine.hh:334
transport::NodePtr node
Node for communication.
Definition: PhysicsEngine.hh:309
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:92
ContactManager * contactManager
Class that handles all contacts generated by the physics engine.
Definition: PhysicsEngine.hh:325