33 #ifndef DART_DYNAMICS_SHAPENODE_HPP_
34 #define DART_DYNAMICS_SHAPENODE_HPP_
36 #include <Eigen/Dense>
45 class CollisionAspect;
60 const Eigen::Isometry3d& oldTransform,
61 const Eigen::Isometry3d& newTransform)>;
99 void setOffset(
const Eigen::Vector3d& offset);
113 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
123 const std::string&
name =
"ShapeNode");
BodyPropPtr properties
Definition: SdfParser.cpp:80
std::string * name
Definition: SkelParser.cpp:1697
detail::CompositeProperties Properties
Definition: Composite.hpp:56
Definition: Signal.hpp:109
Definition: CompositeData.hpp:186
Definition: CompositeData.hpp:107
BodyNode class represents a single node of the skeleton.
Definition: BodyNode.hpp:79
Definition: CompositeNode.hpp:96
The Node class is a base class for BodyNode and any object that attaches to a BodyNode.
Definition: Node.hpp:81
Definition: ShapeNode.hpp:49
Eigen::Vector3d getRelativeTranslation() const
Get translation of this shape node relative to the parent frame.
Definition: ShapeNode.cpp:123
Eigen::Matrix3d getRelativeRotation() const
Get rotation of this shape node relative to the parent frame.
Definition: ShapeNode.cpp:102
void setRelativeTranslation(const Eigen::Vector3d &translation)
Set translation of this shape node relative to the parent frame.
Definition: ShapeNode.cpp:108
const Properties getShapeNodeProperties() const
Get the Properties of this ShapeNode.
Definition: ShapeNode.cpp:46
Node * cloneNode(BodyNode *parent) const override
Create a clone of this ShapeNode.
Definition: ShapeNode.cpp:174
Eigen::Vector3d getOffset() const
Same as getRelativeTranslation()
Definition: ShapeNode.cpp:129
void setRelativeTransform(const Eigen::Isometry3d &transform) override
Set transformation of this shape node relative to the parent frame.
Definition: ShapeNode.cpp:77
void setProperties(const Properties &properties)
Set the Properties of this ShapeNode.
Definition: ShapeNode.cpp:40
void setOffset(const Eigen::Vector3d &offset)
Same as setRelativeTranslation(offset)
Definition: ShapeNode.cpp:117
ShapeNode * asShapeNode() override
Definition: ShapeNode.cpp:135
void setRelativeRotation(const Eigen::Matrix3d &rotation)
Set rotation of this shape node relative to the parent frame.
Definition: ShapeNode.cpp:93
void copy(const ShapeNode &other)
Copy the properties of another ShapeNode.
Definition: ShapeNode.cpp:52
ShapeNode & operator=(const ShapeNode &other)
Same as copy(const ShapeNode&)
Definition: ShapeNode.cpp:70
ShapeNode(BodyNode *bodyNode, const BasicProperties &properties)
Constructor used by the Skeleton class.
Definition: ShapeNode.cpp:147
virtual ~ShapeNode()=default
Destructor.
dart::collision::fcl::Vector3 transform(const dart::collision::fcl::Transform3 &t, const dart::collision::fcl::Vector3 &v)
Transforms a 3-dim vector by a transform and returns the result.
Definition: BackwardCompatibility.cpp:133
std::shared_ptr< Shape > ShapePtr
Definition: SmartPointer.hpp:81
Definition: BulletCollisionDetector.cpp:65