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(
152 public:
virtual void SetWorldCFM(
double _cfm);
158 public:
virtual void SetWorldERP(
double _erp);
164 public:
virtual void SetAutoDisableFlag(
bool _autoDisable);
170 public:
virtual void SetContactMaxCorrectingVel(
double _vel);
176 public:
virtual void SetContactSurfaceLayer(
double _layerDepth);
182 public:
virtual void SetMaxContacts(
unsigned int _maxContacts);
251 public:
virtual bool SetParam(
const std::string &_key,
252 const boost::any &_value);
258 public:
virtual boost::any GetParam(
const std::string &_key)
const;
261 public:
virtual void DebugPrint()
const = 0;
270 {
return this->physicsUpdateMutex;}
274 protected:
virtual void OnRequest(ConstRequestPtr &_msg);
278 protected:
virtual void OnPhysicsMsg(ConstPhysicsPtr &_msg);
284 protected: sdf::ElementPtr
sdf;
virtual double GetWorldERP()
: Remove this function, and replace it with a more generic property map
Definition: PhysicsEngine.hh:194
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:66
double realTimeUpdateRate
Real time update rate.
Definition: PhysicsEngine.hh:306
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:82
virtual double GetWorldCFM()
: Remove this function, and replace it with a more generic property map
Definition: PhysicsEngine.hh:188
double targetRealTimeFactor
Target real time factor.
Definition: PhysicsEngine.hh:309
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:43
virtual void UpdatePhysics()
Update the physics engine.
Definition: PhysicsEngine.hh:105
boost::shared_ptr< Shape > ShapePtr
Definition: PhysicsTypes.hh:110
boost::shared_ptr< Subscriber > SubscriberPtr
Definition: TransportTypes.hh:48
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:200
Forward declarations for transport.
WorldPtr world
Pointer to the world.
Definition: PhysicsEngine.hh:281
sdf::ElementPtr sdf
Our SDF values.
Definition: PhysicsEngine.hh:284
boost::recursive_mutex * physicsUpdateMutex
Mutex to protect the update cycle.
Definition: PhysicsEngine.hh:299
default namespace for gazebo
boost::shared_ptr< Collision > CollisionPtr
Definition: PhysicsTypes.hh:94
transport::SubscriberPtr physicsSub
Subscribe to the physics topic.
Definition: PhysicsEngine.hh:293
virtual void Reset()
Rest the physics engine.
Definition: PhysicsEngine.hh:60
transport::SubscriberPtr requestSub
Subscribe to the request topic.
Definition: PhysicsEngine.hh:296
virtual double GetContactMaxCorrectingVel()
: Remove this function, and replace it with a more generic property map.
Definition: PhysicsEngine.hh:206
boost::shared_ptr< World > WorldPtr
Definition: PhysicsTypes.hh:78
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:98
boost::shared_ptr< Node > NodePtr
Definition: TransportTypes.hh:52
boost::recursive_mutex * GetPhysicsUpdateMutex() const
returns a pointer to the PhysicsEngine::physicsUpdateMutex.
Definition: PhysicsEngine.hh:269
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:218
virtual double GetContactSurfaceLayer()
: Remove this function, and replace it with a more generic property map.
Definition: PhysicsEngine.hh:212
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:44
transport::PublisherPtr responsePub
Response publisher.
Definition: PhysicsEngine.hh:290
double maxStepSize
Real time update rate.
Definition: PhysicsEngine.hh:312
#define GAZEBO_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system.hh:48
transport::NodePtr node
Node for communication.
Definition: PhysicsEngine.hh:287
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:90
ContactManager * contactManager
Class that handles all contacts generated by the physics engine.
Definition: PhysicsEngine.hh:303