33 #ifndef DART_DYNAMICS_SHAPENODE_HPP_ 34 #define DART_DYNAMICS_SHAPENODE_HPP_ 36 #include <Eigen/Dense> 38 #include "dart/common/Signal.hpp" 39 #include "dart/dynamics/detail/ShapeNode.hpp" 45 class CollisionAspect;
55 const ShapePtr& oldShape,
56 const ShapePtr& newShape)>;
60 const Eigen::Isometry3d& oldTransform,
61 const Eigen::Isometry3d& newTransform)>;
99 void setOffset(
const Eigen::Vector3d& offset);
111 const ShapeNode* asShapeNode()
const override;
113 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
122 const ShapePtr& shape,
123 const std::string& name =
"ShapeNode");
133 #endif // DART_DYNAMICS_SHAPENODE_HPP_ void copy(const ShapeNode &other)
Copy the properties of another ShapeNode.
Definition: ShapeNode.cpp:52
void setRelativeTransform(const Eigen::Isometry3d &transform) override
Set transformation of this shape node relative to the parent frame.
Definition: ShapeNode.cpp:77
The Node class is a base class for BodyNode and any object that attaches to a BodyNode.
Definition: Node.hpp:79
Definition: CompositeData.hpp:106
Eigen::Vector3d getRelativeTranslation() const
Get translation of this shape node relative to the parent frame.
Definition: ShapeNode.cpp:123
void setRelativeRotation(const Eigen::Matrix3d &rotation)
Set rotation of this shape node relative to the parent frame.
Definition: ShapeNode.cpp:93
ShapeNode & operator=(const ShapeNode &other)
Same as copy(const ShapeNode&)
Definition: ShapeNode.cpp:70
Eigen::Matrix3d getRelativeRotation() const
Get rotation of this shape node relative to the parent frame.
Definition: ShapeNode.cpp:102
void setProperties(const Properties &properties)
Set the Properties of this ShapeNode.
Definition: ShapeNode.cpp:40
virtual ~ShapeNode()=default
Destructor.
Definition: Aspect.cpp:40
Definition: Signal.hpp:109
void setOffset(const Eigen::Vector3d &offset)
Same as setRelativeTranslation(offset)
Definition: ShapeNode.cpp:117
Definition: CompositeNode.hpp:95
Definition: ShapeNode.hpp:48
const Properties getShapeNodeProperties() const
Get the Properties of this ShapeNode.
Definition: ShapeNode.cpp:46
void setRelativeTranslation(const Eigen::Vector3d &translation)
Set translation of this shape node relative to the parent frame.
Definition: ShapeNode.cpp:108
BodyNode class represents a single node of the skeleton.
Definition: BodyNode.hpp:74
Node * cloneNode(BodyNode *parent) const override
Create a clone of this ShapeNode.
Definition: ShapeNode.cpp:174
ShapeNode(BodyNode *bodyNode, const BasicProperties &properties)
Constructor used by the Skeleton class.
Definition: ShapeNode.cpp:147
Eigen::Vector3d getOffset() const
Same as getRelativeTranslation()
Definition: ShapeNode.cpp:129
Definition: CompositeData.hpp:185