ODE physics engine. More...
#include <ODEPhysics.hh>
Public Member Functions | |
ODEPhysics (WorldPtr world) | |
Constructor. | |
virtual | ~ODEPhysics () |
Destructor. | |
void | Collide (ODECollision *collision1, ODECollision *collision2, dContactGeom *contactCollisions) |
Collide two collisions. | |
virtual CollisionPtr | CreateCollision (const std::string &_shapeType, LinkPtr _parent) |
Create a collision. | |
void | CreateContact (ODECollision *collision1, ODECollision *collision2) |
Not yet implemented. | |
virtual JointPtr | CreateJoint (const std::string &type, ModelPtr _parent) |
Create a new joint. | |
virtual LinkPtr | CreateLink (ModelPtr _parent) |
Create a new body. | |
virtual ShapePtr | CreateShape (const std::string &_shapeType, CollisionPtr _collision) |
Create a collision physics::Shape object given its type. | |
virtual void | DebugPrint () const |
Debug print out of the physic engine state. | |
virtual void | Fini () |
Finilize the ODE engine. | |
double | GetContactMaxCorrectingVel () |
access functions to set ODE parameters | |
double | GetContactSurfaceLayer () |
access functions to set ODE parameters | |
math::Vector3 | GetGravity () const |
Get gravity vector. | |
int | GetMaxContacts () |
access functions to set ODE parameters | |
int | GetSORPGSIters () |
access functions to set ODE parameters | |
int | GetSORPGSPreconIters () |
access functions to set ODE parameters | |
double | GetSORPGSW () |
access functions to set ODE parameters | |
dSpaceID | GetSpaceId () const |
Return the space id. | |
virtual double | GetStepTime () |
Get the simulation step time. | |
virtual std::string | GetStepType () const |
Get the step type. | |
double | GetWorldCFM () |
access functions to set ODE parameters | |
double | GetWorldERP () |
access functions to set ODE parameters | |
dWorldID | GetWorldId () |
Get the world id. | |
virtual void | Init () |
Initialize the ODE engine. | |
virtual void | InitForThread () |
Init the engine for threads. | |
virtual void | Load (sdf::ElementPtr _sdf) |
Load the ODE engine. | |
void | ProcessContactFeedback (ContactFeedback *feedback, msgs::Contact *_msg) |
process contact feedbacks into physics::ContactFeedback | |
void | Reset () |
Empties dynamically created contact joints. | |
void | SetContactMaxCorrectingVel (double vel) |
access functions to set ODE parameters | |
void | SetContactSurfaceLayer (double layer_depth) |
access functions to set ODE parameters | |
virtual void | SetGravity (const gazebo::math::Vector3 &gravity) |
Set the gavity vector. | |
void | SetMaxContacts (unsigned int max_contacts) |
access functions to set ODE parameters | |
void | SetSORPGSIters (unsigned int iters) |
access functions to set ODE parameters | |
void | SetSORPGSPreconIters (unsigned int iters) |
access functions to set ODE parameters | |
void | SetSORPGSW (double w) |
access functions to set ODE parameters | |
void | SetStepTime (double _value) |
Set the step time. | |
virtual void | SetStepType (const std::string &_type) |
Set the step type. | |
void | SetWorldCFM (double cfm) |
access functions to set ODE parameters | |
void | SetWorldERP (double erp) |
access functions to set ODE parameters | |
virtual void | UpdateCollision () |
Update the ODE collision. | |
virtual void | UpdatePhysics () |
Update the ODE engine. | |
Public Member Functions inherited from gazebo::physics::PhysicsEngine | |
PhysicsEngine (WorldPtr _world) | |
Default constructor. | |
virtual | ~PhysicsEngine () |
Destructor. | |
CollisionPtr | CreateCollision (const std::string &_shapeType, const std::string &_linkName) |
Create a collision. | |
virtual bool | GetAutoDisableFlag () |
: Remove this function, and replace it with a more generic property map | |
math::Vector3 | GetGravity () const |
Return the gavity vector. | |
boost::recursive_mutex * | GetPhysicsUpdateMutex () const |
returns a pointer to the PhysicsEngine::physicsUpdateMutex. | |
double | GetUpdatePeriod () |
Get the simulation update period. | |
double | GetUpdateRate () |
Get the simulation update rate. | |
virtual void | SetAutoDisableFlag (bool _autoDisable) |
: Remove this function, and replace it with a more generic property map | |
virtual void | SetMaxContacts (double _maxContacts) |
: Remove this function, and replace it with a more generic property map | |
void | SetUpdateRate (double _value) |
Set the simulation update rate. | |
Static Public Member Functions | |
static void | ConvertMass (InertialPtr _interial, void *odeMass) |
Convert an odeMass to Mass. | |
static void | ConvertMass (void *odeMass, InertialPtr _inertial) |
Convert an odeMass to Mass. | |
Protected Member Functions | |
virtual void | OnPhysicsMsg (ConstPhysicsPtr &) |
act on a msgs::Physics message request | |
virtual void | OnRequest (ConstRequestPtr &) |
act on a msgs::Request for physics | |
Additional Inherited Members | |
Protected Attributes inherited from gazebo::physics::PhysicsEngine | |
transport::PublisherPtr | contactPub |
Contact publisher. | |
transport::NodePtr | node |
Node for communication. | |
transport::SubscriberPtr | physicsSub |
Subscribe to the physics topic. | |
boost::recursive_mutex * | physicsUpdateMutex |
Mutex to protect the update cycle. | |
transport::SubscriberPtr | requestSub |
Subscribe to the request topic. | |
transport::PublisherPtr | responsePub |
Response publisher. | |
sdf::ElementPtr | sdf |
Our SDF values. | |
WorldPtr | world |
Pointer to the world. | |
ODE physics engine.
gazebo::physics::ODEPhysics::ODEPhysics | ( | WorldPtr | world | ) |
Constructor.
|
virtual |
Destructor.
void gazebo::physics::ODEPhysics::Collide | ( | ODECollision * | collision1, |
ODECollision * | collision2, | ||
dContactGeom * | contactCollisions | ||
) |
Collide two collisions.
|
static |
Convert an odeMass to Mass.
|
static |
Convert an odeMass to Mass.
|
virtual |
Create a collision.
Implements gazebo::physics::PhysicsEngine.
void gazebo::physics::ODEPhysics::CreateContact | ( | ODECollision * | collision1, |
ODECollision * | collision2 | ||
) |
Not yet implemented.
|
virtual |
Create a new joint.
Implements gazebo::physics::PhysicsEngine.
Create a new body.
Implements gazebo::physics::PhysicsEngine.
|
virtual |
Create a collision physics::Shape object given its type.
Implements gazebo::physics::PhysicsEngine.
|
virtual |
Debug print out of the physic engine state.
Implements gazebo::physics::PhysicsEngine.
|
virtual |
Finilize the ODE engine.
Reimplemented from gazebo::physics::PhysicsEngine.
|
virtual |
access functions to set ODE parameters
Reimplemented from gazebo::physics::PhysicsEngine.
|
virtual |
access functions to set ODE parameters
Reimplemented from gazebo::physics::PhysicsEngine.
math::Vector3 gazebo::physics::ODEPhysics::GetGravity | ( | ) | const |
Get gravity vector.
|
virtual |
access functions to set ODE parameters
Reimplemented from gazebo::physics::PhysicsEngine.
|
virtual |
access functions to set ODE parameters
Reimplemented from gazebo::physics::PhysicsEngine.
|
virtual |
access functions to set ODE parameters
Reimplemented from gazebo::physics::PhysicsEngine.
|
virtual |
access functions to set ODE parameters
Reimplemented from gazebo::physics::PhysicsEngine.
dSpaceID gazebo::physics::ODEPhysics::GetSpaceId | ( | ) | const |
Return the space id.
|
virtual |
Get the simulation step time.
Implements gazebo::physics::PhysicsEngine.
|
virtual |
Get the step type.
|
virtual |
access functions to set ODE parameters
Reimplemented from gazebo::physics::PhysicsEngine.
|
virtual |
access functions to set ODE parameters
Reimplemented from gazebo::physics::PhysicsEngine.
dWorldID gazebo::physics::ODEPhysics::GetWorldId | ( | ) |
Get the world id.
|
virtual |
Initialize the ODE engine.
Implements gazebo::physics::PhysicsEngine.
|
virtual |
Init the engine for threads.
Implements gazebo::physics::PhysicsEngine.
|
virtual |
Load the ODE engine.
Reimplemented from gazebo::physics::PhysicsEngine.
|
protectedvirtual |
act on a msgs::Physics message request
Reimplemented from gazebo::physics::PhysicsEngine.
|
protectedvirtual |
act on a msgs::Request for physics
Reimplemented from gazebo::physics::PhysicsEngine.
void gazebo::physics::ODEPhysics::ProcessContactFeedback | ( | ContactFeedback * | feedback, |
msgs::Contact * | _msg | ||
) |
process contact feedbacks into physics::ContactFeedback
|
virtual |
Empties dynamically created contact joints.
Reimplemented from gazebo::physics::PhysicsEngine.
|
virtual |
access functions to set ODE parameters
Reimplemented from gazebo::physics::PhysicsEngine.
|
virtual |
access functions to set ODE parameters
Reimplemented from gazebo::physics::PhysicsEngine.
|
virtual |
Set the gavity vector.
Implements gazebo::physics::PhysicsEngine.
void gazebo::physics::ODEPhysics::SetMaxContacts | ( | unsigned int | max_contacts | ) |
access functions to set ODE parameters
|
virtual |
access functions to set ODE parameters
Reimplemented from gazebo::physics::PhysicsEngine.
|
virtual |
access functions to set ODE parameters
Reimplemented from gazebo::physics::PhysicsEngine.
|
virtual |
access functions to set ODE parameters
Reimplemented from gazebo::physics::PhysicsEngine.
|
virtual |
Set the step time.
Implements gazebo::physics::PhysicsEngine.
|
virtual |
Set the step type.
|
virtual |
access functions to set ODE parameters
Reimplemented from gazebo::physics::PhysicsEngine.
|
virtual |
access functions to set ODE parameters
Reimplemented from gazebo::physics::PhysicsEngine.
|
virtual |
Update the ODE collision.
Implements gazebo::physics::PhysicsEngine.
|
virtual |
Update the ODE engine.
Reimplemented from gazebo::physics::PhysicsEngine.