DART 6.6.2
Loading...
Searching...
No Matches
World.hpp
Go to the documentation of this file.
1/*
2 * Copyright (c) 2011-2018, The DART development contributors
3 * All rights reserved.
4 *
5 * The list of contributors can be found at:
6 * https://github.com/dartsim/dart/blob/master/LICENSE
7 *
8 * This file is provided under the following "BSD-style" License:
9 * Redistribution and use in source and binary forms, with or
10 * without modification, are permitted provided that the following
11 * conditions are met:
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * This code incorporates portions of Open Dynamics Engine
19 * (Copyright (c) 2001-2004, Russell L. Smith. All rights
20 * reserved.) and portions of FCL (Copyright (c) 2011, Willow
21 * Garage, Inc. All rights reserved.), which were released under
22 * the same BSD license as below
23 *
24 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
25 * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
26 * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
27 * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
28 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
29 * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
30 * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
31 * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
32 * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
33 * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
34 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
35 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
36 * POSSIBILITY OF SUCH DAMAGE.
37 */
38
39#ifndef DART_SIMULATION_WORLD_HPP_
40#define DART_SIMULATION_WORLD_HPP_
41
42#include <string>
43#include <vector>
44#include <set>
45
46#include <Eigen/Dense>
47
48#include "dart/common/Timer.hpp"
55
56namespace dart {
57
58namespace integration {
59class Integrator;
60} // namespace integration
61
62namespace dynamics {
63class Skeleton;
64} // namespace dynamics
65
66namespace constraint {
67class ConstraintSolver;
68} // namespace constraint
69
70namespace collision {
71class CollisionResult;
72} // namespace collision
73
74namespace simulation {
75
77class World : public virtual common::Subject
78{
79public:
80
82 = common::Signal<void(const std::string& _oldName,
83 const std::string& _newName)>;
84
85 //--------------------------------------------------------------------------
86 // Constructor and Destructor
87 //--------------------------------------------------------------------------
88
90 static std::shared_ptr<World> create(const std::string& name = "world");
91
93 World(const std::string& _name = "world");
94
96 virtual ~World();
97
103 std::shared_ptr<World> clone() const;
104
105 //--------------------------------------------------------------------------
106 // Properties
107 //--------------------------------------------------------------------------
108
110 const std::string& setName(const std::string& _newName);
111
113 const std::string& getName() const;
114
116 void setGravity(const Eigen::Vector3d& _gravity);
117
119 const Eigen::Vector3d& getGravity() const;
120
122 void setTimeStep(double _timeStep);
123
125 double getTimeStep() const;
126
127 //--------------------------------------------------------------------------
128 // Structural Properties
129 //--------------------------------------------------------------------------
130
132 dynamics::SkeletonPtr getSkeleton(std::size_t _index) const;
133
137 dynamics::SkeletonPtr getSkeleton(const std::string& _name) const;
138
140 std::size_t getNumSkeletons() const;
141
143 std::string addSkeleton(const dynamics::SkeletonPtr& _skeleton);
144
146 void removeSkeleton(const dynamics::SkeletonPtr& _skeleton);
147
150 std::set<dynamics::SkeletonPtr> removeAllSkeletons();
151
153 bool hasSkeleton(const dynamics::ConstSkeletonPtr& skeleton) const;
154
156 int getIndex(int _index) const;
157
159 dynamics::SimpleFramePtr getSimpleFrame(std::size_t _index) const;
160
162 dynamics::SimpleFramePtr getSimpleFrame(const std::string& _name) const;
163
165 std::size_t getNumSimpleFrames() const;
166
168 std::string addSimpleFrame(const dynamics::SimpleFramePtr& _frame);
169
172
175 std::set<dynamics::SimpleFramePtr> removeAllSimpleFrames();
176
177 //--------------------------------------------------------------------------
178 // Collision checking
179 //--------------------------------------------------------------------------
180
182 DART_DEPRECATED(6.0)
183 bool checkCollision(bool checkAllCollisions);
184
190 bool checkCollision(
191 const collision::CollisionOption& option
192 = collision::CollisionOption(false, 1u, nullptr),
193 collision::CollisionResult* result = nullptr);
194
199 const collision::CollisionResult& getLastCollisionResult() const;
200
201 //--------------------------------------------------------------------------
202 // Simulation
203 //--------------------------------------------------------------------------
204
206 void reset();
207
211 void step(bool _resetCommand = true);
212
214 void setTime(double _time);
215
217 double getTime() const;
218
223 int getSimFrames() const;
224
225 //--------------------------------------------------------------------------
226 // Constraint
227 //--------------------------------------------------------------------------
228
230 constraint::ConstraintSolver* getConstraintSolver() const;
231
233 void bake();
234
237
238protected:
239
242 const dynamics::ConstMetaSkeletonPtr& _skeleton);
243
245 void handleSimpleFrameNameChange(const dynamics::Entity* _entity);
246
248 std::string mName;
249
251 std::vector<dynamics::SkeletonPtr> mSkeletons;
252
253 std::map<dynamics::ConstMetaSkeletonPtr,
254 dynamics::SkeletonPtr> mMapForSkeletons;
255
258 std::vector<common::Connection> mNameConnectionsForSkeletons;
259
261 dart::common::NameManager<dynamics::SkeletonPtr> mNameMgrForSkeletons;
262
264 std::vector<dynamics::SimpleFramePtr> mSimpleFrames;
265
268 std::vector<common::Connection> mNameConnectionsForSimpleFrames;
269
271 std::map<const dynamics::SimpleFrame*, dynamics::SimpleFramePtr> mSimpleFrameToShared;
272
274 dart::common::NameManager<dynamics::SimpleFramePtr> mNameMgrForSimpleFrames;
275
280 std::vector<int> mIndices;
281
283 Eigen::Vector3d mGravity;
284
286 double mTimeStep;
287
289 double mTime;
290
293
295 constraint::ConstraintSolver* mConstraintSolver;
296
299
300 //--------------------------------------------------------------------------
301 // Signals
302 //--------------------------------------------------------------------------
304
305public:
306 //--------------------------------------------------------------------------
307 // Slot registers
308 //--------------------------------------------------------------------------
309 common::SlotRegister<NameChangedSignal> onNameChanged;
310
311};
312
313typedef std::shared_ptr<World> WorldPtr;
314
315} // namespace simulation
316} // namespace dart
317
318#endif // DART_SIMULATION_WORLD_HPP_
#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