82class 
World : public virtual common::Subject
 
   88                            const std::string& _newName)>;
 
   91  template <
typename... Args>
 
   92  static WorldPtr create(Args&&... args);
 
   99  static std::shared_ptr<World> create(
const std::string& 
name = 
"world");
 
  102  World(
const std::string& _name = 
"world");
 
  112  std::shared_ptr<World> clone() 
const;
 
  119  const std::string& setName(
const std::string& _newName);
 
  122  const std::string& getName() 
const;
 
  125  void setGravity(
const Eigen::Vector3d& _gravity);
 
  128  const Eigen::Vector3d& getGravity() 
const;
 
  131  void setTimeStep(
double _timeStep);
 
  134  double getTimeStep() 
const;
 
  149  std::size_t getNumSkeletons() 
const;
 
  159  std::set<dynamics::SkeletonPtr> removeAllSkeletons();
 
  165  int getIndex(
int _index) 
const;
 
  174  std::size_t getNumSimpleFrames() 
const;
 
  184  std::set<dynamics::SimpleFramePtr> removeAllSimpleFrames();
 
  192  bool checkCollision(
bool checkAllCollisions);
 
  200      const collision::CollisionOption& 
option 
  201          = collision::CollisionOption(false, 1u, 
nullptr),
 
  202      collision::CollisionResult* 
result = 
nullptr);
 
  208  const collision::CollisionResult& getLastCollisionResult() const;
 
  220  void step(
bool _resetCommand = true);
 
  223  void setTime(
double _time);
 
  226  double getTime() const;
 
  232  int getSimFrames() const;
 
  239  void setConstraintSolver(constraint::UniqueConstraintSolverPtr solver);
 
  242  constraint::ConstraintSolver* getConstraintSolver() const;
 
  253  void handleSkeletonNameChange(
 
  254      const dynamics::ConstMetaSkeletonPtr& _skeleton);
 
  257  void handleSimpleFrameNameChange(const dynamics::Entity* _entity);
 
  263  std::vector<dynamics::SkeletonPtr> mSkeletons;
 
  265  std::map<dynamics::ConstMetaSkeletonPtr,
 
  266           dynamics::SkeletonPtr> mMapForSkeletons;
 
  270  std::vector<common::Connection> mNameConnectionsForSkeletons;
 
  273  dart::common::NameManager<dynamics::SkeletonPtr> mNameMgrForSkeletons;
 
  276  std::vector<dynamics::SimpleFramePtr> mSimpleFrames;
 
  280  std::vector<common::Connection> mNameConnectionsForSimpleFrames;
 
  283  std::map<const dynamics::SimpleFrame*, dynamics::SimpleFramePtr> mSimpleFrameToShared;
 
  286  dart::common::NameManager<dynamics::SimpleFramePtr> mNameMgrForSimpleFrames;
 
  292  std::vector<
int> mIndices;
 
  307  std::unique_ptr<constraint::ConstraintSolver> mConstraintSolver;
 
 
const CollisionOption & option
Collision option of DART.
Definition FCLCollisionDetector.cpp:154