DART  6.10.1
Frame.hpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011-2021, 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 SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
19  * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
20  * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
21  * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
23  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
24  * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
25  * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
26  * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  */
32 
33 #ifndef DART_DYNAMICS_FRAME_HPP_
34 #define DART_DYNAMICS_FRAME_HPP_
35 
36 #include <set>
37 
38 #include <Eigen/Geometry>
39 
40 #include "dart/dynamics/Entity.hpp"
41 #include "dart/math/MathTypes.hpp"
42 
43 namespace dart {
44 namespace dynamics {
45 
57 class Frame : public virtual Entity
58 {
59 public:
60  friend class Entity;
61  friend class WorldFrame;
62  friend class ShapeFrame;
63 
64  Frame(const Frame&) = delete;
65 
67  ~Frame() override;
68 
69  static Frame* World();
70 
71  // Shared pointer version for Pythong binding. In the current binding setting,
72  // Frame is always held in std::shared_ptr. This means it will double free
73  // when Frame* World() is used because Frame* World() returns a raw pointer of
74  // static instance. This workaround wouldn't heart the performance too much
75  // because it only creates one additional WorldFrame instance and one
76  // shared_ptr to hold it.
77  static std::shared_ptr<Frame> WorldShared();
78 
79  //--------------------------------------------------------------------------
80  // Transform
81  //--------------------------------------------------------------------------
82 
84  virtual const Eigen::Isometry3d& getRelativeTransform() const = 0;
85 
87  const Eigen::Isometry3d& getWorldTransform() const;
88 
90  Eigen::Isometry3d getTransform(
91  const Frame* _withRespectTo = Frame::World()) const;
92 
95  Eigen::Isometry3d getTransform(
96  const Frame* withRespectTo, const Frame* inCoordinatesOf) const;
97 
98  //-------------------------------------------------------------------------
99  // Velocity
100  //-------------------------------------------------------------------------
101 
104  virtual const Eigen::Vector6d& getRelativeSpatialVelocity() const = 0;
105 
108  const Eigen::Vector6d& getSpatialVelocity() const;
109 
113  const Frame* _relativeTo, const Frame* _inCoordinatesOf) const;
114 
117  Eigen::Vector6d getSpatialVelocity(const Eigen::Vector3d& _offset) const;
118 
121  const Eigen::Vector3d& _offset,
122  const Frame* _relativeTo,
123  const Frame* _inCoordinatesOf) const;
124 
127  Eigen::Vector3d getLinearVelocity(
128  const Frame* _relativeTo = Frame::World(),
129  const Frame* _inCoordinatesOf = Frame::World()) const;
130 
134  Eigen::Vector3d getLinearVelocity(
135  const Eigen::Vector3d& _offset,
136  const Frame* _relativeTo = Frame::World(),
137  const Frame* _inCoordinatesOf = Frame::World()) const;
138 
141  Eigen::Vector3d getAngularVelocity(
142  const Frame* _relativeTo = Frame::World(),
143  const Frame* _inCoordinatesOf = Frame::World()) const;
144 
145  //--------------------------------------------------------------------------
146  // Acceleration
147  //--------------------------------------------------------------------------
148 
152 
165 
169  virtual const Eigen::Vector6d& getPartialAcceleration() const = 0;
170 
174 
178  const Frame* _relativeTo, const Frame* _inCoordinatesOf) const;
179 
183  Eigen::Vector6d getSpatialAcceleration(const Eigen::Vector3d& _offset) const;
184 
187  const Eigen::Vector3d& _offset,
188  const Frame* _relativeTo,
189  const Frame* _inCoordinatesOf) const;
190 
193  Eigen::Vector3d getLinearAcceleration(
194  const Frame* _relativeTo = Frame::World(),
195  const Frame* _inCoordinatesOf = Frame::World()) const;
196 
197  Eigen::Vector3d getLinearAcceleration(
198  const Eigen::Vector3d& _offset,
199  const Frame* _relativeTo = Frame::World(),
200  const Frame* _inCoordinatesOf = Frame::World()) const;
201 
204  Eigen::Vector3d getAngularAcceleration(
205  const Frame* _relativeTo = Frame::World(),
206  const Frame* _inCoordinatesOf = Frame::World()) const;
207 
208  //--------------------------------------------------------------------------
209  // Relationships
210  //--------------------------------------------------------------------------
211 
216  const std::set<Entity*>& getChildEntities();
217 
222  const std::set<const Entity*> getChildEntities() const;
223 
225  std::size_t getNumChildEntities() const;
226 
230  const std::set<Frame*>& getChildFrames();
231 
235  std::set<const Frame*> getChildFrames() const;
236 
238  std::size_t getNumChildFrames() const;
239 
241  bool isShapeFrame() const;
242 
245  virtual ShapeFrame* asShapeFrame();
246 
249  virtual const ShapeFrame* asShapeFrame() const;
250 
252  bool isWorld() const;
253 
256  virtual void dirtyTransform() override;
257 
259  virtual void dirtyVelocity() override;
260 
263  virtual void dirtyAcceleration() override;
264 
265 protected:
269  {
271  };
272 
274  explicit Frame(Frame* _refFrame);
275 
277  Frame();
278 
280  explicit Frame(ConstructAbstractTag);
281 
282  // Documentation inherited
283  virtual void changeParentFrame(Frame* _newParentFrame) override;
284 
288  virtual void processNewEntity(Entity* _newChildEntity);
289 
292  virtual void processRemovedEntity(Entity* _oldChildEntity);
293 
294 private:
297  {
299  };
300 
302  explicit Frame(ConstructWorldTag);
303 
304 protected:
309  mutable Eigen::Isometry3d mWorldTransform;
310 
315 
320 
322  std::set<Frame*> mChildFrames;
323 
325  std::set<Entity*> mChildEntities;
326 
327 private:
329  const bool mAmWorld;
330 
333 
334 public:
335  // To get byte-aligned Eigen vectors
336  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
337 };
338 
343 class WorldFrame : public Frame
344 {
345 public:
346  friend class Frame;
347 
349  const Eigen::Isometry3d& getRelativeTransform() const override final;
350 
352  const Eigen::Vector6d& getRelativeSpatialVelocity() const override final;
353 
355  const Eigen::Vector6d& getRelativeSpatialAcceleration() const override final;
356 
358  const Eigen::Vector6d& getPrimaryRelativeAcceleration() const override final;
359 
361  const Eigen::Vector6d& getPartialAcceleration() const override final;
362 
363  const std::string& setName(const std::string& name) override final;
364 
365  const std::string& getName() const override final;
366 
367 private:
369  explicit WorldFrame();
370 
371 private:
373  const Eigen::Isometry3d mRelativeTf;
374 
376  static const Eigen::Vector6d mZero;
377 
378 public:
379  // To get byte-aligned Eigen vectors
380  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
381 };
383 
384 } // namespace dynamics
385 } // namespace dart
386 
387 #endif // DART_DYNAMICS_FRAME_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
std::string * name
Definition: SkelParser.cpp:1697
Entity class is a base class for any objects that exist in the kinematic tree structure of DART.
Definition: Entity.hpp:61
ConstructAbstractTag
Used when constructing a pure abstract class, because calling the Entity constructor is just a formal...
Definition: Entity.hpp:165
The Frame class serves as the backbone of DART's kinematic tree structure.
Definition: Frame.hpp:58
std::set< Entity * > mChildEntities
Container of this Frame's child Entities.
Definition: Frame.hpp:325
bool isWorld() const
Returns true if this Frame is the World Frame.
Definition: Frame.cpp:475
std::size_t getNumChildEntities() const
Get the number of Entities that are currently children of this Frame.
Definition: Frame.cpp:433
virtual ShapeFrame * asShapeFrame()
Convert 'this' into a ShapeFrame pointer if Frame is a ShapeFrame, otherwise return nullptr.
Definition: Frame.cpp:463
const std::set< Entity * > & getChildEntities()
Get a container with the Entities that are children of this Frame.
Definition: Frame.cpp:421
bool mAmShapeFrame
Contains whether or not this is a ShapeFrame.
Definition: Frame.hpp:332
virtual void changeParentFrame(Frame *_newParentFrame) override
Used by derived classes to change their parent frames.
Definition: Frame.cpp:565
virtual void processNewEntity(Entity *_newChildEntity)
Called during a parent Frame change to allow extensions of the Frame class to handle new children in ...
Definition: Frame.cpp:607
virtual const Eigen::Vector6d & getPartialAcceleration() const =0
The Featherstone ABI algorithm exploits a component of the spatial acceleration which we refer to as ...
Eigen::Vector3d getAngularAcceleration(const Frame *_relativeTo=Frame::World(), const Frame *_inCoordinatesOf=Frame::World()) const
Get the angular portion of classical acceleration of this Frame relative to some other Frame.
Definition: Frame.cpp:403
ConstructAbstractTag
Used when constructing a pure abstract class, because calling the Frame constructor is just a formali...
Definition: Frame.hpp:269
@ ConstructAbstract
Definition: Frame.hpp:270
const bool mAmWorld
Contains whether or not this is the World Frame.
Definition: Frame.hpp:329
Eigen::Isometry3d mWorldTransform
World transform of this Frame.
Definition: Frame.hpp:309
Eigen::Vector3d getLinearVelocity(const Frame *_relativeTo=Frame::World(), const Frame *_inCoordinatesOf=Frame::World()) const
Get the linear portion of classical velocity of this Frame relative to some other Frame.
Definition: Frame.cpp:227
virtual const Eigen::Vector6d & getRelativeSpatialVelocity() const =0
Get the spatial velocity of this Frame relative to its parent Frame, in its own coordinates.
std::set< Frame * > mChildFrames
Container of this Frame's child Frames.
Definition: Frame.hpp:322
Eigen::Isometry3d getTransform(const Frame *_withRespectTo=Frame::World()) const
Get the transform of this Frame with respect to some other Frame.
Definition: Frame.cpp:109
virtual void dirtyVelocity() override
Notify the velocity updates of this Frame and all its children are needed.
Definition: Frame.cpp:500
static Frame * World()
Definition: Frame.cpp:73
virtual void processRemovedEntity(Entity *_oldChildEntity)
Called when a child Entity is removed from its parent Frame.
Definition: Frame.cpp:613
std::size_t getNumChildFrames() const
Get the number of Frames that are currently children of this Frame.
Definition: Frame.cpp:451
const std::set< Frame * > & getChildFrames()
Get a container with the Frames that are children of this Frame.
Definition: Frame.cpp:439
ConstructWorldTag
Used when constructing the World.
Definition: Frame.hpp:297
@ ConstructWorld
Definition: Frame.hpp:298
virtual const Eigen::Vector6d & getPrimaryRelativeAcceleration() const =0
The Featherstone ABI algorithm exploits a component of the spatial acceleration which we refer to as ...
const Eigen::Vector6d & getSpatialVelocity() const
Get the total spatial velocity of this Frame in the coordinates of this Frame.
Definition: Frame.cpp:140
const Eigen::Isometry3d & getWorldTransform() const
Get the transform of this Frame with respect to the World Frame.
Definition: Frame.cpp:93
Eigen::Vector3d getLinearAcceleration(const Frame *_relativeTo=Frame::World(), const Frame *_inCoordinatesOf=Frame::World()) const
Get the linear portion of classical acceleration of this Frame relative to some other Frame.
Definition: Frame.cpp:361
~Frame() override
Destructor.
Definition: Frame.cpp:45
Eigen::Vector6d mVelocity
Total velocity of this Frame, in the coordinates of this Frame.
Definition: Frame.hpp:314
Frame()
Default constructor, delegates to Frame(ConstructAbstract_t)
Definition: Frame.cpp:549
Eigen::Vector3d getAngularVelocity(const Frame *_relativeTo=Frame::World(), const Frame *_inCoordinatesOf=Frame::World()) const
Get the angular portion of classical velocity of this Frame relative to some other Frame.
Definition: Frame.cpp:243
bool isShapeFrame() const
Returns true if this Frame is a ShapeFrame.
Definition: Frame.cpp:457
Frame(const Frame &)=delete
const Eigen::Vector6d & getSpatialAcceleration() const
Get the total spatial acceleration of this Frame in the coordinates of this Frame.
Definition: Frame.cpp:250
static std::shared_ptr< Frame > WorldShared()
Definition: Frame.cpp:80
virtual const Eigen::Vector6d & getRelativeSpatialAcceleration() const =0
Get the spatial acceleration of this Frame relative to its parent Frame, in the coordinates of this F...
virtual const Eigen::Isometry3d & getRelativeTransform() const =0
Get the transform of this Frame with respect to its parent Frame.
Eigen::Vector6d mAcceleration
Total acceleration of this Frame, in the coordinates of this Frame.
Definition: Frame.hpp:319
virtual void dirtyAcceleration() override
Notify the acceleration updates of this Frame and all its children are needed.
Definition: Frame.cpp:519
virtual void dirtyTransform() override
Notify the transformation updates of this Frame and all its children are needed.
Definition: Frame.cpp:481
Definition: ShapeFrame.hpp:192
The WorldFrame class is a class that is used internally to create the singleton World Frame.
Definition: Frame.hpp:344
const Eigen::Isometry3d mRelativeTf
This is set to Identity and never changes.
Definition: Frame.hpp:373
const Eigen::Vector6d & getRelativeSpatialVelocity() const override final
Always returns a zero vector.
Definition: Frame.cpp:640
const std::string & getName() const override final
Return the name of this Entity.
Definition: Frame.cpp:673
const Eigen::Isometry3d & getRelativeTransform() const override final
Always returns the Identity Transform.
Definition: Frame.cpp:634
const Eigen::Vector6d & getRelativeSpatialAcceleration() const override final
Always returns a zero vector.
Definition: Frame.cpp:646
static const Eigen::Vector6d mZero
This is set to a Zero vector and never changes.
Definition: Frame.hpp:376
const Eigen::Vector6d & getPartialAcceleration() const override final
Always returns a zero vector.
Definition: Frame.cpp:658
const Eigen::Vector6d & getPrimaryRelativeAcceleration() const override final
Always returns a zero vector.
Definition: Frame.cpp:652
const std::string & setName(const std::string &name) override final
Set name.
Definition: Frame.cpp:664
Definition: Random-impl.hpp:92
Matrix< double, 6, 1 > Vector6d
Definition: MathTypes.hpp:49
Definition: BulletCollisionDetector.cpp:65
Definition: SharedLibraryManager.hpp:46