DART  6.10.1
dart::simulation::World Class Reference

class World More...

#include <World.hpp>

Inheritance diagram for dart::simulation::World:
dart::common::Subject

Public Types

using NameChangedSignal = common::Signal< void(const std::string &_oldName, const std::string &_newName)>
 

Public Member Functions

 World (const std::string &_name="world")
 Constructor. More...
 
virtual ~World ()
 Destructor. More...
 
std::shared_ptr< Worldclone () const
 Create a clone of this World. More...
 
const std::string & setName (const std::string &_newName)
 Set the name of this World. More...
 
const std::string & getName () const
 Get the name of this World. More...
 
void setGravity (const Eigen::Vector3d &_gravity)
 Set gravity. More...
 
const Eigen::Vector3d & getGravity () const
 Get gravity. More...
 
void setTimeStep (double _timeStep)
 Set time step. More...
 
double getTimeStep () const
 Get time step. More...
 
dynamics::SkeletonPtr getSkeleton (std::size_t _index) const
 Get the indexed skeleton. More...
 
dynamics::SkeletonPtr getSkeleton (const std::string &_name) const
 Find a Skeleton by name. More...
 
std::size_t getNumSkeletons () const
 Get the number of skeletons. More...
 
std::string addSkeleton (const dynamics::SkeletonPtr &_skeleton)
 Add a skeleton to this world. More...
 
void removeSkeleton (const dynamics::SkeletonPtr &_skeleton)
 Remove a skeleton from this world. More...
 
std::set< dynamics::SkeletonPtrremoveAllSkeletons ()
 Remove all the skeletons in this world, and return a set of shared pointers to them, in case you want to recycle them. More...
 
bool hasSkeleton (const dynamics::ConstSkeletonPtr &skeleton) const
 Returns whether this World contains a Skeleton. More...
 
bool hasSkeleton (const std::string &skeletonName) const
 Returns whether this World contains a Skeleton named skeletonName. More...
 
int getIndex (int _index) const
 Get the dof index for the indexed skeleton. More...
 
dynamics::SimpleFramePtr getSimpleFrame (std::size_t _index) const
 Get the indexed Entity. More...
 
dynamics::SimpleFramePtr getSimpleFrame (const std::string &_name) const
 Find an Entity by name. More...
 
std::size_t getNumSimpleFrames () const
 Get the number of Entities. More...
 
std::string addSimpleFrame (const dynamics::SimpleFramePtr &_frame)
 Add an Entity to this world. More...
 
void removeSimpleFrame (const dynamics::SimpleFramePtr &_frame)
 Remove a SimpleFrame from this world. More...
 
std::set< dynamics::SimpleFramePtrremoveAllSimpleFrames ()
 Remove all SimpleFrames in this world, and return a set of shared pointers to them, in case you want to recycle them. More...
 
bool checkCollision (bool checkAllCollisions)
 Deprecated. Please use checkCollision(~) instead. More...
 
bool checkCollision (const collision::CollisionOption &option=collision::CollisionOption(false, 1u, nullptr), collision::CollisionResult *result=nullptr)
 Perform collision checking with 'option' over all the feasible collision pairs in this World, and the result will be stored 'result'. More...
 
const collision::CollisionResultgetLastCollisionResult () const
 Return the collision checking result of the last simulation step. More...
 
void reset ()
 Reset the time, frame counter and recorded histories. More...
 
void step (bool _resetCommand=true)
 Calculate the dynamics and integrate the world for one step. More...
 
void setTime (double _time)
 Set current time. More...
 
double getTime () const
 Get current time. More...
 
int getSimFrames () const
 Get the number of simulated frames. More...
 
void setConstraintSolver (constraint::UniqueConstraintSolverPtr solver)
 Sets the constraint solver. More...
 
constraint::ConstraintSolvergetConstraintSolver ()
 Get the constraint solver. More...
 
const constraint::ConstraintSolvergetConstraintSolver () const
 Get the constraint solver. More...
 
void bake ()
 Bake simulated current state and store it into mRecording. More...
 
RecordinggetRecording ()
 Get recording. More...
 

Static Public Member Functions

template<typename... Args>
static WorldPtr create (Args &&... args)
 Creates World as shared_ptr. More...
 
static std::shared_ptr< Worldcreate (const std::string &name="world")
 Creates a World. More...
 

Public Attributes

common::SlotRegister< NameChangedSignalonNameChanged
 

Protected Member Functions

void handleSkeletonNameChange (const dynamics::ConstMetaSkeletonPtr &_skeleton)
 Register when a Skeleton's name is changed. More...
 
void handleSimpleFrameNameChange (const dynamics::Entity *_entity)
 Register when a SimpleFrame's name is changed. More...
 
void sendDestructionNotification () const
 Send a destruction notification to all Observers. More...
 
void addObserver (Observer *_observer) const
 Add an Observer to the list of Observers. More...
 
void removeObserver (Observer *_observer) const
 Remove an Observer from the list of Observers. More...
 

Protected Attributes

std::string mName
 Name of this World. More...
 
std::vector< dynamics::SkeletonPtrmSkeletons
 Skeletons in this world. More...
 
std::map< dynamics::ConstMetaSkeletonPtr, dynamics::SkeletonPtrmMapForSkeletons
 
std::vector< common::ConnectionmNameConnectionsForSkeletons
 Connections for noticing changes in Skeleton names TODO(MXG): Consider putting this functionality into NameManager. More...
 
dart::common::NameManager< dynamics::SkeletonPtrmNameMgrForSkeletons
 NameManager for keeping track of Skeletons. More...
 
std::vector< dynamics::SimpleFramePtrmSimpleFrames
 Entities in this world. More...
 
std::vector< common::ConnectionmNameConnectionsForSimpleFrames
 Connections for noticing changes in Frame names TODO(MXG): Consider putting this functionality into NameManager. More...
 
std::map< const dynamics::SimpleFrame *, dynamics::SimpleFramePtrmSimpleFrameToShared
 Map from raw SimpleFrame pointers to their shared_ptrs. More...
 
dart::common::NameManager< dynamics::SimpleFramePtrmNameMgrForSimpleFrames
 NameManager for keeping track of Entities. More...
 
std::vector< int > mIndices
 The first indeices of each skeleton's dof in mDofs. More...
 
Eigen::Vector3d mGravity
 Gravity. More...
 
double mTimeStep
 Simulation time step. More...
 
double mTime
 Current simulation time. More...
 
int mFrame
 Current simulation frame number. More...
 
std::unique_ptr< constraint::ConstraintSolvermConstraintSolver
 Constraint solver. More...
 
RecordingmRecording
 
NameChangedSignal mNameChangedSignal
 
std::set< Observer * > mObservers
 List of current Observers. More...
 

Detailed Description

class World

Member Typedef Documentation

◆ NameChangedSignal

using dart::simulation::World::NameChangedSignal = common::Signal<void( const std::string& _oldName, const std::string& _newName)>

Constructor & Destructor Documentation

◆ World()

dart::simulation::World::World ( const std::string &  _name = "world")

Constructor.

◆ ~World()

dart::simulation::World::~World ( )
virtual

Destructor.

Member Function Documentation

◆ addObserver()

void dart::common::Subject::addObserver ( Observer _observer) const
protectedinherited

Add an Observer to the list of Observers.

◆ addSimpleFrame()

std::string dart::simulation::World::addSimpleFrame ( const dynamics::SimpleFramePtr _frame)

Add an Entity to this world.

◆ addSkeleton()

std::string dart::simulation::World::addSkeleton ( const dynamics::SkeletonPtr _skeleton)

Add a skeleton to this world.

◆ bake()

void dart::simulation::World::bake ( )

Bake simulated current state and store it into mRecording.

◆ checkCollision() [1/2]

bool dart::simulation::World::checkCollision ( bool  checkAllCollisions)

Deprecated. Please use checkCollision(~) instead.

◆ checkCollision() [2/2]

bool dart::simulation::World::checkCollision ( const collision::CollisionOption option = collision::CollisionOption(false, 1u, nullptr),
collision::CollisionResult result = nullptr 
)

Perform collision checking with 'option' over all the feasible collision pairs in this World, and the result will be stored 'result'.

If no argument is passed in then it will return just whether there is collision or not without the contact information such as contact point, normal, and penetration depth.

◆ clone()

WorldPtr dart::simulation::World::clone ( ) const

Create a clone of this World.

All Skeletons and SimpleFrames that are held by this World will be copied over.

◆ create() [1/2]

template<typename... Args>
WorldPtr dart::simulation::World::create ( Args &&...  args)
static

Creates World as shared_ptr.

◆ create() [2/2]

std::shared_ptr< World > dart::simulation::World::create ( const std::string &  name = "world")
static

Creates a World.

◆ getConstraintSolver() [1/2]

constraint::ConstraintSolver * dart::simulation::World::getConstraintSolver ( )

Get the constraint solver.

◆ getConstraintSolver() [2/2]

const constraint::ConstraintSolver * dart::simulation::World::getConstraintSolver ( ) const

Get the constraint solver.

◆ getGravity()

const Eigen::Vector3d & dart::simulation::World::getGravity ( ) const

Get gravity.

◆ getIndex()

int dart::simulation::World::getIndex ( int  _index) const

Get the dof index for the indexed skeleton.

◆ getLastCollisionResult()

const collision::CollisionResult & dart::simulation::World::getLastCollisionResult ( ) const

Return the collision checking result of the last simulation step.

If this world hasn't stepped forward yet, then the result would be empty. Note that this function does not return the collision checking result of World::checkCollision().

◆ getName()

const std::string & dart::simulation::World::getName ( ) const

Get the name of this World.

◆ getNumSimpleFrames()

std::size_t dart::simulation::World::getNumSimpleFrames ( ) const

Get the number of Entities.

◆ getNumSkeletons()

std::size_t dart::simulation::World::getNumSkeletons ( ) const

Get the number of skeletons.

◆ getRecording()

Recording * dart::simulation::World::getRecording ( )

Get recording.

◆ getSimFrames()

int dart::simulation::World::getSimFrames ( ) const

Get the number of simulated frames.

TODO(MXG): I think the name of this function is much too similar to getSimpleFrame()

◆ getSimpleFrame() [1/2]

dynamics::SimpleFramePtr dart::simulation::World::getSimpleFrame ( const std::string &  _name) const

Find an Entity by name.

◆ getSimpleFrame() [2/2]

dynamics::SimpleFramePtr dart::simulation::World::getSimpleFrame ( std::size_t  _index) const

Get the indexed Entity.

◆ getSkeleton() [1/2]

dynamics::SkeletonPtr dart::simulation::World::getSkeleton ( const std::string &  _name) const

Find a Skeleton by name.

Parameters
[in]_nameThe name of the Skeleton you are looking for.
Returns
If the skeleton does not exist then return nullptr.

◆ getSkeleton() [2/2]

dynamics::SkeletonPtr dart::simulation::World::getSkeleton ( std::size_t  _index) const

Get the indexed skeleton.

◆ getTime()

double dart::simulation::World::getTime ( ) const

Get current time.

◆ getTimeStep()

double dart::simulation::World::getTimeStep ( ) const

Get time step.

◆ handleSimpleFrameNameChange()

void dart::simulation::World::handleSimpleFrameNameChange ( const dynamics::Entity _entity)
protected

Register when a SimpleFrame's name is changed.

◆ handleSkeletonNameChange()

void dart::simulation::World::handleSkeletonNameChange ( const dynamics::ConstMetaSkeletonPtr _skeleton)
protected

Register when a Skeleton's name is changed.

◆ hasSkeleton() [1/2]

bool dart::simulation::World::hasSkeleton ( const dynamics::ConstSkeletonPtr skeleton) const

Returns whether this World contains a Skeleton.

◆ hasSkeleton() [2/2]

bool dart::simulation::World::hasSkeleton ( const std::string &  skeletonName) const

Returns whether this World contains a Skeleton named skeletonName.

◆ removeAllSimpleFrames()

std::set< dynamics::SimpleFramePtr > dart::simulation::World::removeAllSimpleFrames ( )

Remove all SimpleFrames in this world, and return a set of shared pointers to them, in case you want to recycle them.

◆ removeAllSkeletons()

std::set< dynamics::SkeletonPtr > dart::simulation::World::removeAllSkeletons ( )

Remove all the skeletons in this world, and return a set of shared pointers to them, in case you want to recycle them.

◆ removeObserver()

void dart::common::Subject::removeObserver ( Observer _observer) const
protectedinherited

Remove an Observer from the list of Observers.

◆ removeSimpleFrame()

void dart::simulation::World::removeSimpleFrame ( const dynamics::SimpleFramePtr _frame)

Remove a SimpleFrame from this world.

◆ removeSkeleton()

void dart::simulation::World::removeSkeleton ( const dynamics::SkeletonPtr _skeleton)

Remove a skeleton from this world.

◆ reset()

void dart::simulation::World::reset ( )

Reset the time, frame counter and recorded histories.

◆ sendDestructionNotification()

void dart::common::Subject::sendDestructionNotification ( ) const
protectedinherited

Send a destruction notification to all Observers.

This will cause all Observers to behave as if this Subject has been permanently deleted, so it should only be called when that behavior is desired.

◆ setConstraintSolver()

void dart::simulation::World::setConstraintSolver ( constraint::UniqueConstraintSolverPtr  solver)

Sets the constraint solver.

Note that the internal properties of solver will be overwritten by this World.

◆ setGravity()

void dart::simulation::World::setGravity ( const Eigen::Vector3d &  _gravity)

Set gravity.

◆ setName()

const std::string & dart::simulation::World::setName ( const std::string &  _newName)

Set the name of this World.

◆ setTime()

void dart::simulation::World::setTime ( double  _time)

Set current time.

◆ setTimeStep()

void dart::simulation::World::setTimeStep ( double  _timeStep)

Set time step.

◆ step()

void dart::simulation::World::step ( bool  _resetCommand = true)

Calculate the dynamics and integrate the world for one step.

Parameters
[in]_resetCommandTrue if you want to reset to zero the joint command after simulation step.

Member Data Documentation

◆ mConstraintSolver

std::unique_ptr<constraint::ConstraintSolver> dart::simulation::World::mConstraintSolver
protected

Constraint solver.

◆ mFrame

int dart::simulation::World::mFrame
protected

Current simulation frame number.

◆ mGravity

Eigen::Vector3d dart::simulation::World::mGravity
protected

Gravity.

◆ mIndices

std::vector<int> dart::simulation::World::mIndices
protected

The first indeices of each skeleton's dof in mDofs.

For example, if this world has three skeletons and their dof are 6, 1 and 2 then the mIndices goes like this: [0 6 7].

◆ mMapForSkeletons

std::map<dynamics::ConstMetaSkeletonPtr, dynamics::SkeletonPtr> dart::simulation::World::mMapForSkeletons
protected

◆ mName

std::string dart::simulation::World::mName
protected

Name of this World.

◆ mNameChangedSignal

NameChangedSignal dart::simulation::World::mNameChangedSignal
protected

◆ mNameConnectionsForSimpleFrames

std::vector<common::Connection> dart::simulation::World::mNameConnectionsForSimpleFrames
protected

Connections for noticing changes in Frame names TODO(MXG): Consider putting this functionality into NameManager.

◆ mNameConnectionsForSkeletons

std::vector<common::Connection> dart::simulation::World::mNameConnectionsForSkeletons
protected

Connections for noticing changes in Skeleton names TODO(MXG): Consider putting this functionality into NameManager.

◆ mNameMgrForSimpleFrames

dart::common::NameManager<dynamics::SimpleFramePtr> dart::simulation::World::mNameMgrForSimpleFrames
protected

NameManager for keeping track of Entities.

◆ mNameMgrForSkeletons

dart::common::NameManager<dynamics::SkeletonPtr> dart::simulation::World::mNameMgrForSkeletons
protected

NameManager for keeping track of Skeletons.

◆ mObservers

std::set<Observer*> dart::common::Subject::mObservers
mutableprotectedinherited

List of current Observers.

◆ mRecording

Recording* dart::simulation::World::mRecording
protected

◆ mSimpleFrames

std::vector<dynamics::SimpleFramePtr> dart::simulation::World::mSimpleFrames
protected

Entities in this world.

◆ mSimpleFrameToShared

std::map<const dynamics::SimpleFrame*, dynamics::SimpleFramePtr> dart::simulation::World::mSimpleFrameToShared
protected

Map from raw SimpleFrame pointers to their shared_ptrs.

◆ mSkeletons

std::vector<dynamics::SkeletonPtr> dart::simulation::World::mSkeletons
protected

Skeletons in this world.

◆ mTime

double dart::simulation::World::mTime
protected

Current simulation time.

◆ mTimeStep

double dart::simulation::World::mTimeStep
protected

Simulation time step.

◆ onNameChanged

common::SlotRegister<NameChangedSignal> dart::simulation::World::onNameChanged