39 #ifndef DART_SIMULATION_WORLD_HPP_
40 #define DART_SIMULATION_WORLD_HPP_
46 #include <Eigen/Dense>
61 namespace integration {
69 namespace constraint {
70 class ConstraintSolver;
77 namespace simulation {
87 const std::string& _oldName,
const std::string& _newName)>;
90 template <
typename... Args>
98 static std::shared_ptr<World>
create(
const std::string&
name =
"world");
101 World(
const std::string& _name =
"world");
108 std::shared_ptr<World>
clone()
const;
115 const std::string&
setName(
const std::string& _newName);
118 const std::string&
getName()
const;
121 void setGravity(
const Eigen::Vector3d& _gravity);
161 bool hasSkeleton(
const std::string& skeletonName)
const;
199 const collision::CollisionOption&
option
200 = collision::CollisionOption(false, 1u,
nullptr),
219 void step(
bool _resetCommand = true);
333 #include "dart/simulation/detail/World-impl.hpp"
#define DART_DECLARE_CLASS_WITH_VIRTUAL_BASE_END
Definition: ClassWithVirtualBase.hpp:44
#define DART_DECLARE_CLASS_WITH_VIRTUAL_BASE_BEGIN
Definition: ClassWithVirtualBase.hpp:43
#define DART_DEPRECATED(version)
Definition: Deprecated.hpp:51
const CollisionOption & option
Collision option of DART.
Definition: FCLCollisionDetector.cpp:157
CollisionResult * result
Collision result of DART.
Definition: FCLCollisionDetector.cpp:160
std::string * name
Definition: SkelParser.cpp:1697
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:84
virtual ~World()
Destructor.
Definition: World.cpp:80
std::size_t getNumSkeletons() const
Get the number of skeletons.
Definition: World.cpp:283
std::map< dynamics::ConstMetaSkeletonPtr, dynamics::SkeletonPtr > mMapForSkeletons
Definition: World.hpp:270
std::unique_ptr< constraint::ConstraintSolver > mConstraintSolver
Constraint solver.
Definition: World.hpp:312
int getIndex(int _index) const
Get the dof index for the indexed skeleton.
Definition: World.cpp:418
const std::string & getName() const
Get the name of this World.
Definition: World.cpp:244
double getTimeStep() const
Get time step.
Definition: World.cpp:152
void handleSimpleFrameNameChange(const dynamics::Entity *_entity)
Register when a SimpleFrame's name is changed.
Definition: World.cpp:666
std::string mName
Name of this World.
Definition: World.hpp:264
dart::common::NameManager< dynamics::SkeletonPtr > mNameMgrForSkeletons
NameManager for keeping track of Skeletons.
Definition: World.hpp:277
std::map< const dynamics::SimpleFrame *, dynamics::SimpleFramePtr > mSimpleFrameToShared
Map from raw SimpleFrame pointers to their shared_ptrs.
Definition: World.hpp:288
void setTime(double _time)
Set current time.
Definition: World.cpp:209
std::set< dynamics::SkeletonPtr > removeAllSkeletons()
Remove all the skeletons in this world, and return a set of shared pointers to them,...
Definition: World.cpp:389
void step(bool _resetCommand=true)
Calculate the dynamics and integrate the world for one step.
Definition: World.cpp:167
void setConstraintSolver(constraint::UniqueConstraintSolverPtr solver)
Sets the constraint solver.
Definition: World.cpp:557
Eigen::Vector3d mGravity
Gravity.
Definition: World.hpp:300
std::vector< dynamics::SkeletonPtr > mSkeletons
Skeletons in this world.
Definition: World.hpp:267
void removeSkeleton(const dynamics::SkeletonPtr &_skeleton)
Remove a skeleton from this world.
Definition: World.cpp:330
common::SlotRegister< NameChangedSignal > onNameChanged
Definition: World.hpp:326
const collision::CollisionResult & getLastCollisionResult() const
Return the collision checking result of the last simulation step.
Definition: World.cpp:551
std::size_t getNumSimpleFrames() const
Get the number of Entities.
Definition: World.cpp:439
std::vector< dynamics::SimpleFramePtr > mSimpleFrames
Entities in this world.
Definition: World.hpp:280
void setTimeStep(double _timeStep)
Set time step.
Definition: World.cpp:135
double mTimeStep
Simulation time step.
Definition: World.hpp:303
std::vector< int > mIndices
The first indeices of each skeleton's dof in mDofs.
Definition: World.hpp:297
void bake()
Bake simulated current state and store it into mRecording.
Definition: World.cpp:586
std::string addSimpleFrame(const dynamics::SimpleFramePtr &_frame)
Add an Entity to this world.
Definition: World.cpp:445
void removeSimpleFrame(const dynamics::SimpleFramePtr &_frame)
Remove a SimpleFrame from this world.
Definition: World.cpp:479
int getSimFrames() const
Get the number of simulated frames.
Definition: World.cpp:221
const std::string & setName(const std::string &_newName)
Set the name of this World.
Definition: World.cpp:227
void reset()
Reset the time, frame counter and recorded histories.
Definition: World.cpp:158
std::vector< common::Connection > mNameConnectionsForSimpleFrames
Connections for noticing changes in Frame names TODO(MXG): Consider putting this functionality into N...
Definition: World.hpp:284
int mFrame
Current simulation frame number.
Definition: World.hpp:309
NameChangedSignal mNameChangedSignal
Definition: World.hpp:320
bool checkCollision(bool checkAllCollisions)
Deprecated. Please use checkCollision(~) instead.
Definition: World.cpp:530
const Eigen::Vector3d & getGravity() const
Get gravity.
Definition: World.cpp:262
void setGravity(const Eigen::Vector3d &_gravity)
Set gravity.
Definition: World.cpp:250
constraint::ConstraintSolver * getConstraintSolver()
Get the constraint solver.
Definition: World.cpp:574
std::shared_ptr< World > clone() const
Create a clone of this World.
Definition: World.cpp:92
World(const std::string &_name="world")
Constructor.
Definition: World.cpp:62
void handleSkeletonNameChange(const dynamics::ConstMetaSkeletonPtr &_skeleton)
Register when a Skeleton's name is changed.
Definition: World.cpp:616
dynamics::SkeletonPtr getSkeleton(std::size_t _index) const
Get the indexed skeleton.
Definition: World.cpp:268
std::set< dynamics::SimpleFramePtr > removeAllSimpleFrames()
Remove all SimpleFrames in this world, and return a set of shared pointers to them,...
Definition: World.cpp:513
dart::common::NameManager< dynamics::SimpleFramePtr > mNameMgrForSimpleFrames
NameManager for keeping track of Entities.
Definition: World.hpp:291
std::string addSkeleton(const dynamics::SkeletonPtr &_skeleton)
Add a skeleton to this world.
Definition: World.cpp:289
bool hasSkeleton(const dynamics::ConstSkeletonPtr &skeleton) const
Returns whether this World contains a Skeleton.
Definition: World.cpp:405
Recording * getRecording()
Get recording.
Definition: World.cpp:610
std::vector< common::Connection > mNameConnectionsForSkeletons
Connections for noticing changes in Skeleton names TODO(MXG): Consider putting this functionality int...
Definition: World.hpp:274
static WorldPtr create(Args &&... args)
Creates World as shared_ptr.
Definition: World-impl.hpp:49
Recording * mRecording
Definition: World.hpp:315
double getTime() const
Get current time.
Definition: World.cpp:215
dynamics::SimpleFramePtr getSimpleFrame(std::size_t _index) const
Get the indexed Entity.
Definition: World.cpp:424
double mTime
Current simulation time.
Definition: World.hpp:306
#define DART_COMMON_DECLARE_SHARED_WEAK(X)
Definition: SmartPointer.hpp:41
Definition: Random-impl.hpp:92
::fcl::CollisionResult CollisionResult
Definition: BackwardCompatibility.hpp:166
std::unique_ptr< ConstraintSolver > UniqueConstraintSolverPtr
Definition: SmartPointer.hpp:41
std::shared_ptr< const Skeleton > ConstSkeletonPtr
Definition: SmartPointer.hpp:60
std::shared_ptr< const MetaSkeleton > ConstMetaSkeletonPtr
Definition: SmartPointer.hpp:68
std::shared_ptr< SimpleFrame > SimpleFramePtr
Definition: SmartPointer.hpp:53
std::shared_ptr< Skeleton > SkeletonPtr
Definition: SmartPointer.hpp:60
std::shared_ptr< World > WorldPtr
Definition: SmartPointer.hpp:41
Integrator
This attribute selects the numerical integrator to be used.
Definition: Types.hpp:72
Definition: BulletCollisionDetector.cpp:65
Definition: SharedLibraryManager.hpp:46