17 #ifndef _PHYSICSENGINE_HH_
18 #define _PHYSICSENGINE_HH_
20 #include <boost/thread/recursive_mutex.hpp>
21 #include <boost/any.hpp>
23 #include <ignition/transport/Node.hh>
53 public:
virtual void Load(sdf::ElementPtr _sdf);
56 public:
virtual void Init() = 0;
59 public:
virtual void Fini();
94 public:
virtual std::string
GetType()
const = 0;
98 public:
virtual void SetSeed(uint32_t _seed) = 0;
146 const std::string &_shapeType,
LinkPtr _link) = 0;
152 const std::string &_linkName);
170 const ignition::math::Vector3d &_gravity) = 0;
221 public:
virtual bool SetParam(
const std::string &_key,
222 const boost::any &_value);
228 public:
virtual boost::any
GetParam(
const std::string &_key)
const;
235 public:
virtual bool GetParam(
const std::string &_key,
236 boost::any &_value)
const;
252 {
return this->physicsUpdateMutex;}
269 template <
typename T>
274 auto value = boost::any_cast<std::any>(_value);
275 return std::any_cast<T>(value);
277 catch(boost::bad_any_cast &)
279 return boost::any_cast<T>(_value);
285 protected:
virtual void OnRequest(ConstRequestPtr &_msg);
295 protected: sdf::ElementPtr
sdf;
default namespace for gazebo
Forward declarations for transport.
Base class for a physics engine.
Definition: PhysicsEngine.hh:43
double GetMaxStepSize() const
Get max step size.
virtual bool GetParam(const std::string &_key, boost::any &_value) const
Get a parameter from the physics engine with a boolean to indicate success or failure.
virtual ~PhysicsEngine()
Destructor.
virtual CollisionPtr CreateCollision(const std::string &_shapeType, LinkPtr _link)=0
Create a collision.
double targetRealTimeFactor
Target real time factor.
Definition: PhysicsEngine.hh:320
ignition::transport::Node::Publisher responsePubIgn
Response publisher.
Definition: PhysicsEngine.hh:332
virtual void Fini()
Finilize the physics engine.
double GetRealTimeUpdateRate() const
Get real time update rate.
double realTimeUpdateRate
Real time update rate.
Definition: PhysicsEngine.hh:317
void SetMaxStepSize(double _stepSize)
Set max step size.
sdf::ElementPtr GetSDF() const
Get a pointer to the SDF element for this physics engine.
virtual void Reset()
Rest the physics engine.
Definition: PhysicsEngine.hh:62
virtual void Init()=0
Initialize the physics engine.
double maxStepSize
Real time update rate.
Definition: PhysicsEngine.hh:323
virtual void DebugPrint() const =0
Debug print out of the physic engine state.
virtual void UpdatePhysics()
Update the physics engine.
Definition: PhysicsEngine.hh:132
transport::NodePtr node
Node for communication.
Definition: PhysicsEngine.hh:298
virtual void OnRequest(ConstRequestPtr &_msg)
virtual callback for gztopic "~/request".
transport::PublisherPtr responsePub
Response publisher.
Definition: PhysicsEngine.hh:301
transport::SubscriberPtr requestSub
Subscribe to the request topic.
Definition: PhysicsEngine.hh:307
ignition::transport::Node nodeIgn
Ignition node for communication.
Definition: PhysicsEngine.hh:329
PhysicsEngine(WorldPtr _world)
Default constructor.
virtual std::string GetType() const =0
Return the physics engine type (ode|bullet|dart|simbody).
void SetRealTimeUpdateRate(double _rate)
Set real time update rate.
virtual void SetGravity(const ignition::math::Vector3d &_gravity)=0
Set the gravity vector.
WorldPtr World() const
Get a pointer to the world.
ContactManager * GetContactManager() const
Get a pointer to the contact manger.
virtual ShapePtr CreateShape(const std::string &_shapeType, CollisionPtr _collision)=0
Create a physics::Shape object.
virtual bool GetAutoDisableFlag()
\TODO: Remove this function, and replace it with a more generic property map
Definition: PhysicsEngine.hh:188
transport::SubscriberPtr physicsSub
Subscribe to the physics topic.
Definition: PhysicsEngine.hh:304
boost::recursive_mutex * GetPhysicsUpdateMutex() const
returns a pointer to the PhysicsEngine::physicsUpdateMutex.
Definition: PhysicsEngine.hh:251
sdf::ElementPtr sdf
Our SDF values.
Definition: PhysicsEngine.hh:295
virtual void OnPhysicsMsg(ConstPhysicsPtr &_msg)
virtual callback for gztopic "~/physics".
virtual JointPtr CreateJoint(const std::string &_type, ModelPtr _parent=ModelPtr())=0
Create a new joint.
double GetTargetRealTimeFactor() const
Get target real time factor.
virtual boost::any GetParam(const std::string &_key) const
Get an parameter of the physics engine.
virtual void SetAutoDisableFlag(bool _autoDisable)
\TODO: Remove this function, and replace it with a more generic property map
virtual void UpdateCollision()=0
Update the physics engine collision.
virtual ModelPtr CreateModel(BasePtr _base)
Create a new model.
WorldPtr world
Pointer to the world.
Definition: PhysicsEngine.hh:292
virtual void Load(sdf::ElementPtr _sdf)
Load the physics engine.
double GetUpdatePeriod()
Get the simulation update period.
virtual bool SetParam(const std::string &_key, const boost::any &_value)
Set a parameter of the physics engine.
void SetTargetRealTimeFactor(double _factor)
Set target real time factor.
boost::recursive_mutex * physicsUpdateMutex
Mutex to protect the update cycle.
Definition: PhysicsEngine.hh:310
CollisionPtr CreateCollision(const std::string &_shapeType, const std::string &_linkName)
Create a collision.
virtual LinkPtr CreateLink(ModelPtr _parent)=0
Create a new body.
ContactManager * contactManager
Class that handles all contacts generated by the physics engine.
Definition: PhysicsEngine.hh:314
virtual void SetSeed(uint32_t _seed)=0
Set the random number seed for the physics engine.
virtual void InitForThread()=0
Init the engine for threads.
static T any_cast(const boost::any &_value)
Helper function for performing any_cast operations in SetParam.
Definition: PhysicsEngine.hh:270
virtual void SetMaxContacts(unsigned int _maxContacts)
\TODO: Remove this function, and replace it with a more generic property map
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:110
boost::shared_ptr< Collision > CollisionPtr
Definition: PhysicsTypes.hh:114
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:78
boost::shared_ptr< Shape > ShapePtr
Definition: PhysicsTypes.hh:142
boost::shared_ptr< World > WorldPtr
Definition: PhysicsTypes.hh:90
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:94
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:118
boost::shared_ptr< Subscriber > SubscriberPtr
Definition: TransportTypes.hh:53
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:49
boost::shared_ptr< Node > NodePtr
Definition: TransportTypes.hh:57
Forward declarations for the common classes.
Definition: Animation.hh:27