39#ifndef DART_SIMULATION_WORLD_HPP_
40#define DART_SIMULATION_WORLD_HPP_
58namespace integration {
67class ConstraintSolver;
83 const std::string& _newName)>;
90 static std::shared_ptr<World>
create(
const std::string&
name =
"world");
93 World(
const std::string& _name =
"world");
103 std::shared_ptr<World>
clone()
const;
110 const std::string&
setName(
const std::string& _newName);
113 const std::string&
getName()
const;
116 void setGravity(
const Eigen::Vector3d& _gravity);
191 const collision::CollisionOption&
option
192 = collision::CollisionOption(false, 1u,
nullptr),
193 collision::CollisionResult*
result =
nullptr);
211 void step(
bool _resetCommand = true);
242 const dynamics::ConstMetaSkeletonPtr& _skeleton);
253 std::map<dynamics::ConstMetaSkeletonPtr,
#define DART_DEPRECATED(version)
Definition Deprecated.hpp:51
const CollisionOption & option
Collision option of DART.
Definition FCLCollisionDetector.cpp:154
CollisionResult * result
Collision result of DART.
Definition FCLCollisionDetector.cpp:157
std::string * name
Definition SkelParser.cpp:1642
The Subject class is a base class for any object that wants to report when it gets destroyed.
Definition Subject.hpp:58
class Recording
Definition Recording.hpp:58
class World
Definition World.hpp:78
virtual ~World()
Destructor.
Definition World.cpp:77
std::size_t getNumSkeletons() const
Get the number of skeletons.
Definition World.cpp:279
std::map< dynamics::ConstMetaSkeletonPtr, dynamics::SkeletonPtr > mMapForSkeletons
Definition World.hpp:254
constraint::ConstraintSolver * mConstraintSolver
Constraint solver.
Definition World.hpp:295
int getIndex(int _index) const
Get the dof index for the indexed skeleton.
Definition World.cpp:402
const std::string & getName() const
Get the name of this World.
Definition World.cpp:241
double getTimeStep() const
Get time step.
Definition World.cpp:147
void handleSimpleFrameNameChange(const dynamics::Entity *_entity)
Register when a SimpleFrame's name is changed.
Definition World.cpp:618
std::string mName
Name of this World.
Definition World.hpp:248
static std::shared_ptr< World > create(const std::string &name="world")
Creates a World.
Definition World.cpp:55
dart::common::NameManager< dynamics::SkeletonPtr > mNameMgrForSkeletons
NameManager for keeping track of Skeletons.
Definition World.hpp:261
std::map< const dynamics::SimpleFrame *, dynamics::SimpleFramePtr > mSimpleFrameToShared
Map from raw SimpleFrame pointers to their shared_ptrs.
Definition World.hpp:271
void setTime(double _time)
Set current time.
Definition World.cpp:204
std::set< dynamics::SkeletonPtr > removeAllSkeletons()
Remove all the skeletons in this world, and return a set of shared pointers to them,...
Definition World.cpp:381
void step(bool _resetCommand=true)
Calculate the dynamics and integrate the world for one step.
Definition World.cpp:162
Eigen::Vector3d mGravity
Gravity.
Definition World.hpp:283
std::vector< dynamics::SkeletonPtr > mSkeletons
Skeletons in this world.
Definition World.hpp:251
void removeSkeleton(const dynamics::SkeletonPtr &_skeleton)
Remove a skeleton from this world.
Definition World.cpp:326
common::SlotRegister< NameChangedSignal > onNameChanged
Definition World.hpp:309
const collision::CollisionResult & getLastCollisionResult() const
Return the collision checking result of the last simulation step.
Definition World.cpp:526
std::size_t getNumSimpleFrames() const
Get the number of Entities.
Definition World.cpp:423
std::vector< dynamics::SimpleFramePtr > mSimpleFrames
Entities in this world.
Definition World.hpp:264
void setTimeStep(double _timeStep)
Set time step.
Definition World.cpp:132
double mTimeStep
Simulation time step.
Definition World.hpp:286
std::vector< int > mIndices
The first indeices of each skeleton's dof in mDofs.
Definition World.hpp:280
void bake()
Bake simulated current state and store it into mRecording.
Definition World.cpp:538
std::string addSimpleFrame(const dynamics::SimpleFramePtr &_frame)
Add an Entity to this world.
Definition World.cpp:429
void removeSimpleFrame(const dynamics::SimpleFramePtr &_frame)
Remove a SimpleFrame from this world.
Definition World.cpp:461
int getSimFrames() const
Get the number of simulated frames.
Definition World.cpp:216
const std::string & setName(const std::string &_newName)
Set the name of this World.
Definition World.cpp:222
void reset()
Reset the time, frame counter and recorded histories.
Definition World.cpp:153
std::vector< common::Connection > mNameConnectionsForSimpleFrames
Connections for noticing changes in Frame names TODO(MXG): Consider putting this functionality into N...
Definition World.hpp:268
int mFrame
Current simulation frame number.
Definition World.hpp:292
NameChangedSignal mNameChangedSignal
Definition World.hpp:303
bool checkCollision(bool checkAllCollisions)
Deprecated. Please use checkCollision(~) instead.
Definition World.cpp:506
const Eigen::Vector3d & getGravity() const
Get gravity.
Definition World.cpp:258
void setGravity(const Eigen::Vector3d &_gravity)
Set gravity.
Definition World.cpp:247
std::shared_ptr< World > clone() const
Create a clone of this World.
Definition World.cpp:90
void handleSkeletonNameChange(const dynamics::ConstMetaSkeletonPtr &_skeleton)
Register when a Skeleton's name is changed.
Definition World.cpp:568
dynamics::SkeletonPtr getSkeleton(std::size_t _index) const
Get the indexed skeleton.
Definition World.cpp:264
std::set< dynamics::SimpleFramePtr > removeAllSimpleFrames()
Remove all SimpleFrames in this world, and return a set of shared pointers to them,...
Definition World.cpp:492
dart::common::NameManager< dynamics::SimpleFramePtr > mNameMgrForSimpleFrames
NameManager for keeping track of Entities.
Definition World.hpp:274
std::string addSkeleton(const dynamics::SkeletonPtr &_skeleton)
Add a skeleton to this world.
Definition World.cpp:285
bool hasSkeleton(const dynamics::ConstSkeletonPtr &skeleton) const
Returns wether this World contains a Skeleton.
Definition World.cpp:395
Recording * getRecording()
Get recording.
Definition World.cpp:562
std::vector< common::Connection > mNameConnectionsForSkeletons
Connections for noticing changes in Skeleton names TODO(MXG): Consider putting this functionality int...
Definition World.hpp:258
Recording * mRecording
Definition World.hpp:298
constraint::ConstraintSolver * getConstraintSolver() const
Get the constraint solver.
Definition World.cpp:532
double getTime() const
Get current time.
Definition World.cpp:210
dynamics::SimpleFramePtr getSimpleFrame(std::size_t _index) const
Get the indexed Entity.
Definition World.cpp:408
double mTime
Current simulation time.
Definition World.hpp:289
Definition MathTypes.hpp:47
::fcl::CollisionResult CollisionResult
Definition BackwardCompatibility.hpp:157
std::shared_ptr< const Skeleton > ConstSkeletonPtr
Definition SmartPointer.hpp:60
std::shared_ptr< SimpleFrame > SimpleFramePtr
Definition SmartPointer.hpp:53
std::shared_ptr< Skeleton > SkeletonPtr
Definition SmartPointer.hpp:60
std::shared_ptr< World > WorldPtr
Definition World.hpp:313
Definition BulletCollisionDetector.cpp:63
Definition SharedLibraryManager.hpp:43