RobWorkProject  23.9.11-
Classes | Public Types | Public Member Functions | Protected Member Functions | List of all members
ODESimulator Class Reference

an implementation that use the physics engine ODE to implement the Simulator interface of RWSim. All information into the simulator is derived through RWSim classes. More...

#include <ODESimulator.hpp>

Inherits PhysicsEngine.

Classes

struct  ODEStateStuff
 

Public Types

enum  StepMethod { WorldStep , WorldQuickStep , WorldFast1 }
 
enum  SpaceType { Simple , HashTable , QuadTree }
 type of broad phase collision detection to use
 
typedef rw::core::Ptr< ODESimulatorPtr
 smart pointer type
 
- Public Types inherited from PhysicsEngine
typedef rw::core::Ptr< PhysicsEnginePtr
 smart pointer type of PhysicsEngine
 

Public Member Functions

 ODESimulator ()
 empty constructor
 
 ODESimulator (dynamics::DynamicWorkCell::Ptr dwc, rw::core::Ptr< rwsim::contacts::BaseContactDetector > detector=NULL)
 constructor More...
 
virtual ~ODESimulator ()
 destructor
 
void load (rwsim::dynamics::DynamicWorkCell::Ptr dwc)
 adds dynamic workcell More...
 
bool setContactDetector (rw::core::Ptr< rwsim::contacts::BaseContactDetector > detector)
 Change the contact detector used by the engine. More...
 
void setStepMethod (StepMethod method)
 sets the ODE step method that should be used for stepping
 
void step (double dt, rw::kinematics::State &state)
 Performs a step and updates the state. More...
 
void resetScene (rw::kinematics::State &state)
 reset velocity and acceleration of all bodies to 0. And sets the position of all bodies to that described in state More...
 
void initPhysics (rw::kinematics::State &state)
 initialize simulator physics with state More...
 
void exitPhysics ()
 cleans up the allocated storage fo bullet physics More...
 
double getTime ()
 gets the the current simulated time More...
 
void DWCChangedListener (dynamics::DynamicWorkCell::DWCEventType type, boost::any data)
 
void setEnabled (dynamics::Body::Ptr body, bool enabled)
 
void setDynamicsEnabled (dynamics::Body::Ptr body, bool enabled)
 
drawable::SimulatorDebugRender::Ptr createDebugRender ()
 create a debug render for the specific implementation More...
 
virtual rw::core::PropertyMapgetPropertyMap ()
 properties of the physics engine More...
 
void emitPropertyChanged ()
 should be called when properties have been changed and one wants the physics engine to reflect the new properties. More...
 
void addController (rwlibs::simulation::SimulatedController::Ptr controller)
 
bool isInitialized ()
 
void addBody (rwsim::dynamics::Body::Ptr body, rw::kinematics::State &state)
 
void addConstraint (rwsim::dynamics::Constraint::Ptr constraint)
 Add a Constraint between two bodies. More...
 
void addDevice (rwsim::dynamics::DynamicDevice::Ptr device, rw::kinematics::State &state)
 
void addSensor (rwlibs::simulation::SimulatedSensor::Ptr sensor, rw::kinematics::State &state)
 add a simulated sensor to this simulator
 
void removeController (rwlibs::simulation::SimulatedController::Ptr controller)
 
void removeSensor (rwlibs::simulation::SimulatedSensor::Ptr sensor)
 add a simulated sensor to this simulator
 
const rw::kinematics::FramePairMap< std::vector< dynamics::ContactManifold > > & getContactManifoldMap ()
 
std::vector< ODEBody * > & getODEBodies ()
 
dynamics::DynamicWorkCell::Ptr getDynamicWorkCell ()
 
std::vector< rwlibs::simulation::SimulatedSensor::PtrgetSensors ()
 get the list of simulated sensors More...
 
void attach (rwsim::dynamics::Body::Ptr b1, rwsim::dynamics::Body::Ptr b2)
 
void detach (rwsim::dynamics::Body::Ptr b1, rwsim::dynamics::Body::Ptr b2)
 
void setSimulatorLog (rw::core::Ptr< rwsim::log::SimulatorLogScope > log)
 Store internal info during simulation. More...
 
void disableCollision (rwsim::dynamics::Body::Ptr b1, rwsim::dynamics::Body::Ptr b2)
 
void enableCollision (rwsim::dynamics::Body::Ptr b1, rwsim::dynamics::Body::Ptr b2)
 
rw::math::Vector3D getGravity ()
 get current gravity
 
dWorldID getODEWorldId () const
 
void addODEJoint (ODEJoint *odejoint)
 
ODEJointgetODEJoint (rw::models::Joint *joint)
 
void addODEBody (ODEBody *odebody)
 
void addODEBody (dBodyID body)
 
void addODEJoint (dJointID joint)
 
ODEBodygetODEBody (rw::kinematics::Frame *frame)
 
dBodyID getODEBodyId (rw::kinematics::Frame::Ptr frame)
 
dBodyID getODEBodyId (rwsim::dynamics::Body *body)
 
std::vector< ODEDevice * > getODEDevices ()
 
void addEmulatedContact (const rw::math::Vector3D<> &pos, const rw::math::Vector3D<> &force, const rw::math::Vector3D<> &normal, dynamics::Body *b)
 
void setContactLoggingEnabled (bool enable)
 Enables logging of the contact points.
 
boost::unordered_map< std::pair< std::string, std::string >, bool > getContactingBodies ()
 Returns a map of contacting body frame names and their contact points.
 
void handleCollisionBetween (dGeomID o0, dGeomID o1)
 
const std::vector< ODEUtil::TriGeomData * > & getTriMeshs ()
 
std::vector< dynamics::ContactPointgetContacts ()
 
int getContactCnt ()
 
double getMaxSeperatingDistance ()
 
dSpaceID getODESpace ()
 
void addContacts (std::vector< dContact > &contacts, size_t nr_con, ODEBody *dataB1, ODEBody *dataB2)
 
std::vector< ODETactileSensor * > getODESensors (dBodyID odebody)
 
dynamics::MaterialDataMapgetMaterialMap ()
 
dynamics::ContactDataMapgetContactMap ()
 
- Public Member Functions inherited from PhysicsEngine
virtual ~PhysicsEngine ()
 destructor
 
virtual void load (rw::core::Ptr< rwsim::dynamics::DynamicWorkCell > dwc)=0
 adds dynamic workcell
 
virtual void setEnabled (rw::core::Ptr< rwsim::dynamics::Body > body, bool enabled)=0
 
virtual void setDynamicsEnabled (rw::core::Ptr< rwsim::dynamics::Body > body, bool enabled)=0
 disables the dynamics of a body. More...
 
virtual void addController (rw::core::Ptr< rwlibs::simulation::SimulatedController > controller)=0
 add a simulated controller to this simulator
 
virtual void removeController (rw::core::Ptr< rwlibs::simulation::SimulatedController > controller)=0
 removes a simulated controller from this simulator More...
 
virtual void addBody (rw::core::Ptr< rwsim::dynamics::Body > body, rw::kinematics::State &state)=0
 add a body to the physics engine More...
 
virtual void addDevice (rw::core::Ptr< rwsim::dynamics::DynamicDevice > device, rw::kinematics::State &state)=0
 add a dynamic device to the physics engine More...
 
virtual void attach (rw::core::Ptr< rwsim::dynamics::Body > b1, rw::core::Ptr< rwsim::dynamics::Body > b2)=0
 creates a 6dof dynamic constraint between the two bodies b1 and b2 More...
 
virtual void detach (rw::core::Ptr< rwsim::dynamics::Body > b1, rw::core::Ptr< rwsim::dynamics::Body > b2)=0
 removes the 6dof constraint between bodies b1 and b2 if there is any More...
 

Protected Member Functions

void detectCollisionsContactDetector (const rw::kinematics::State &state)
 
bool detectCollisionsRW (rw::kinematics::State &state, bool onlyTestPenetration=false)
 

Detailed Description

an implementation that use the physics engine ODE to implement the Simulator interface of RWSim. All information into the simulator is derived through RWSim classes.

Supported objects types include Rigid, Kinematic and fixed Supported device types include Rigid and Kinematic

The simulation step looks like this

1 updateControllers() 2 updateDevices() // sets the target velocity of devices 3 performContactDetection() 4 performConstraintSolving() 5 updateSensorStates() 6 updateDeviceStates() 7 updateBodyStates()

The ODE physics engine support several engine specific properties. These can be tweaked to obtain higher performance or robustness. ODE specific options:

Only used when RobWork contact generation is used (its the default). MaxSepDistance - float - All triangles within a distance MaxSepDistance is used in the contact generation.

object specific:

SoftLayer - float -

example:

* <Property name="StepMethod">WorldStep</Property>
* <Property name="WorldCFM" type="float">0.000001</Property>
* <Property name="WorldERP" type="float">0.2</Property>
* <Property name="MaxIterations" type="int">100</Property>
* <Property name="ContactSurfaceLayer" type="float">0.001</Property>
*
* <Property name="MaxSepDistance" type="float">0.01</Property>
* <Property name="MaxCorrectingVelocity" type="float">0.1</Property>
* 

Member Enumeration Documentation

◆ StepMethod

enum StepMethod

type of step method, worldStep is direct solver, worldquickstep is faster iterative solver. When dynamically simulating robot arms use worldstep, else simulate chains as kinematic bodies.

Constructor & Destructor Documentation

◆ ODESimulator()

constructor

Parameters
dwc[in] the dynamic workcell for which the simulator should work
detector[in] the contact detector to use

Member Function Documentation

◆ addConstraint()

void addConstraint ( rwsim::dynamics::Constraint::Ptr  constraint)

Add a Constraint between two bodies.

Parameters
constraint[in] a pointer to the RobWork constraint.

◆ createDebugRender()

drawable::SimulatorDebugRender::Ptr createDebugRender ( )
virtual

create a debug render for the specific implementation

Returns
NULL if no render is available else a valid render

Implements PhysicsEngine.

◆ emitPropertyChanged()

void emitPropertyChanged ( )
virtual

should be called when properties have been changed and one wants the physics engine to reflect the new properties.

Implements PhysicsEngine.

◆ exitPhysics()

void exitPhysics ( )
virtual

cleans up the allocated storage fo bullet physics

Implements PhysicsEngine.

◆ getPropertyMap()

virtual rw::core::PropertyMap& getPropertyMap ( )
inlinevirtual

properties of the physics engine

Implements PhysicsEngine.

◆ getSensors()

std::vector<rwlibs::simulation::SimulatedSensor::Ptr> getSensors ( )
inlinevirtual

get the list of simulated sensors

Returns

Implements PhysicsEngine.

◆ getTime()

double getTime ( )
inlinevirtual

gets the the current simulated time

Implements PhysicsEngine.

◆ initPhysics()

void initPhysics ( rw::kinematics::State state)
virtual

initialize simulator physics with state

Implements PhysicsEngine.

◆ load()

adds dynamic workcell

◆ resetScene()

void resetScene ( rw::kinematics::State state)
virtual

reset velocity and acceleration of all bodies to 0. And sets the position of all bodies to that described in state

Implements PhysicsEngine.

◆ setContactDetector()

bool setContactDetector ( rw::core::Ptr< rwsim::contacts::BaseContactDetector detector)
virtual

Change the contact detector used by the engine.

Parameters
detector[in] the contact detector to use (NULL for default contact detection)
Returns
true if engine supports using a ContactDetector and the detector was set successfully.

Implements PhysicsEngine.

◆ setDynamicsEnabled()

void setDynamicsEnabled ( dynamics::Body::Ptr  body,
bool  enabled 
)

Enables or disables a body. A body is automatically enabled if contacts or new interactions with the Body arrise

Parameters
body[in] the body to enable/disable
enabled[in]

◆ setEnabled()

void setEnabled ( dynamics::Body::Ptr  body,
bool  enabled 
)

Enables or disables a body. A body is automatically enabled if contacts or new interactions with the Body arrise

Parameters
body[in] the body to enable/disable
enabled[in]

◆ setSimulatorLog()

void setSimulatorLog ( rw::core::Ptr< rwsim::log::SimulatorLogScope log)
virtual

Store internal info during simulation.

This can be used for debugging, statistics, visualization of internal subresults, timing, benchmark and similar.

Parameters
log[in] a pointer to the log structure to store to.

Reimplemented from PhysicsEngine.

◆ step()

void step ( double  dt,
rw::kinematics::State state 
)
virtual

Performs a step and updates the state.

Implements PhysicsEngine.


The documentation for this class was generated from the following file: