33#ifndef DART_DYNAMICS_FIXEDFRAME_HPP_
34#define DART_DYNAMICS_FIXEDFRAME_HPP_
50 :
public virtual Frame,
58 const Eigen::Isometry3d& relativeTransform
59 = Eigen::Isometry3d::Identity());
97 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
BodyPropPtr properties
Definition SdfParser.cpp:80
Inherit this class to embed Properties into your Composite object.
Definition EmbeddedAspect.hpp:204
typename Aspect::Properties AspectProperties
Definition EmbeddedAspect.hpp:208
VersionCounter is an interface for objects that count their versions.
Definition VersionCounter.hpp:43
The FixedFrame class represents a Frame with zero relative velocity and zero relative acceleration.
Definition FixedFrame.hpp:53
virtual ~FixedFrame()
Destructor.
Definition FixedFrame.cpp:61
const Eigen::Vector6d & getPrimaryRelativeAcceleration() const override
Always returns a zero vector.
Definition FixedFrame.cpp:102
void setAspectProperties(const AspectProperties &properties)
Set the AspectProperties of this FixedFrame.
Definition FixedFrame.cpp:67
static const Eigen::Vector6d mZero
Used for Relative Velocity and Relative Acceleration of this Frame.
Definition FixedFrame.hpp:93
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
virtual void setRelativeTransform(const Eigen::Isometry3d &transform)
Set the relative transform of this FixedFrame.
Definition FixedFrame.cpp:73
const Eigen::Vector6d & getPartialAcceleration() const override
Always returns a zero vector.
Definition FixedFrame.cpp:108
const Eigen::Vector6d & getRelativeSpatialVelocity() const override
Always returns a zero vector.
Definition FixedFrame.cpp:90
const Eigen::Isometry3d & getRelativeTransform() const override
Get the transform of this Frame with respect to its parent Frame.
Definition FixedFrame.cpp:84
The Frame class serves as the backbone of DART's kinematic tree structure.
Definition Frame.hpp:58
ConstructAbstractTag
Used when constructing a pure abstract class, because calling the Frame constructor is just a formali...
Definition Frame.hpp:269
Matrix< double, 6, 1 > Vector6d
Definition MathTypes.hpp:49
Definition BulletCollisionDetector.cpp:65