33 #ifndef DART_DYNAMICS_FRAME_HPP_
34 #define DART_DYNAMICS_FRAME_HPP_
38 #include <Eigen/Geometry>
96 const Frame* withRespectTo,
const Frame* inCoordinatesOf)
const;
113 const Frame* _relativeTo,
const Frame* _inCoordinatesOf)
const;
121 const Eigen::Vector3d& _offset,
122 const Frame* _relativeTo,
123 const Frame* _inCoordinatesOf)
const;
135 const Eigen::Vector3d& _offset,
178 const Frame* _relativeTo,
const Frame* _inCoordinatesOf)
const;
187 const Eigen::Vector3d& _offset,
188 const Frame* _relativeTo,
189 const Frame* _inCoordinatesOf)
const;
198 const Eigen::Vector3d& _offset,
336 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
365 const
std::
string&
getName() const override final;
380 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
#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