33 #ifndef DART_DYNAMICS_FIXEDFRAME_HPP_ 34 #define DART_DYNAMICS_FIXEDFRAME_HPP_ 36 #include "dart/common/EmbeddedAspect.hpp" 37 #include "dart/common/VersionCounter.hpp" 38 #include "dart/dynamics/Frame.hpp" 39 #include "dart/dynamics/detail/FixedFrameAspect.hpp" 48 DART_DECLARE_CLASS_WITH_VIRTUAL_BASE_BEGIN
50 :
public virtual Frame,
58 const Eigen::Isometry3d& relativeTransform
59 = Eigen::Isometry3d::Identity());
93 static const Eigen::Vector6d
mZero;
97 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
99 DART_DECLARE_CLASS_WITH_VIRTUAL_BASE_END
104 #endif // DART_DYNAMICS_FIXEDFRAME_HPP_ void setAspectProperties(const AspectProperties &properties)
Set the AspectProperties of this FixedFrame.
Definition: FixedFrame.cpp:67
The Frame class serves as the backbone of DART's kinematic tree structure.
Definition: Frame.hpp:57
VersionCounter is an interface for objects that count their versions.
Definition: VersionCounter.hpp:42
ConstructAbstractTag
Used when constructing a pure abstract class, because calling the Entity constructor is just a formal...
Definition: Entity.hpp:164
const Eigen::Vector6d & getRelativeSpatialVelocity() const override
Always returns a zero vector.
Definition: FixedFrame.cpp:90
FixedFrame()
Default constructor – calls the Abstract constructor.
Definition: FixedFrame.cpp:114
const Eigen::Vector6d & getRelativeSpatialAcceleration() const override
Always returns a zero vector.
Definition: FixedFrame.cpp:96
Definition: Aspect.cpp:40
virtual ~FixedFrame()
Destructor.
Definition: FixedFrame.cpp:61
The FixedFrame class represents a Frame with zero relative velocity and zero relative acceleration...
Definition: FixedFrame.hpp:49
static const Eigen::Vector6d mZero
Used for Relative Velocity and Relative Acceleration of this Frame.
Definition: FixedFrame.hpp:93
virtual void setRelativeTransform(const Eigen::Isometry3d &transform)
Set the relative transform of this FixedFrame.
Definition: FixedFrame.cpp:73
const Eigen::Vector6d & getPrimaryRelativeAcceleration() const override
Always returns a zero vector.
Definition: FixedFrame.cpp:102
const Eigen::Vector6d & getPartialAcceleration() const override
Always returns a zero vector.
Definition: FixedFrame.cpp:108
Inherit this class to embed Properties into your Composite object.
Definition: EmbeddedAspect.hpp:201
const Eigen::Isometry3d & getRelativeTransform() const override
Get the transform of this Frame with respect to its parent Frame.
Definition: FixedFrame.cpp:84