Go to the documentation of this file.
31 #ifndef TESSERACT_STATE_SOLVER_OFKT_NODE_H
32 #define TESSERACT_STATE_SOLVER_OFKT_NODE_H
36 #include <Eigen/Geometry>
59 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
62 using UPtr = std::unique_ptr<OFKTNode>;
63 using Ptr = std::shared_ptr<OFKTNode>;
64 using ConstPtr = std::shared_ptr<const OFKTNode>;
104 virtual const std::string&
getLinkName()
const = 0;
200 virtual Eigen::Matrix<double, 6, 1>
getLocalTwist()
const = 0;
224 virtual const std::vector<const OFKTNode*>&
getChildren()
const = 0;
228 #endif // TESSERACT_STATE_SOLVER_OFKT_NODE_H
std::shared_ptr< OFKTNode > Ptr
virtual Eigen::Matrix< double, 6, 1 > getLocalTwist() const =0
Return the twist of the node in its local frame.
virtual void storeJointValue(double joint_value)=0
Set the nodes joint value if it has one.
virtual double getJointValue() const =0
Get the current joint value.
virtual ~OFKTNode()=default
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
virtual void setParent(OFKTNode *parent)=0
Set the parent node.
std::shared_ptr< const OFKTNode > ConstPtr
virtual const std::string & getLinkName() const =0
Get the link name associated with the node.
virtual const Eigen::Isometry3d & getStaticTransformation() const =0
Get the nodes static transformation.
virtual const Eigen::Isometry3d & getLocalTransformation() const =0
Get the local transformation: 'L = S * J'.
std::unique_ptr< OFKTNode > UPtr
virtual bool hasJointValueChanged() const =0
Indicates that the joint value has changed and that local and world transformation need to be recompu...
The OFKT node is contains multiple trasformation which are described below.
virtual JointType getType() const =0
Get the type of joint associated with the node.
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
virtual void addChild(OFKTNode *node)=0
Add a child node.
virtual void computeAndStoreLocalTransformation()=0
Compute and save the local transformation 'L = S * J(Joint Value)'.
virtual void removeChild(const OFKTNode *node)=0
Remove a child node assiciated with this node.
virtual std::vector< OFKTNode * > & getChildren()=0
Get a vector of child nodes associated with this node.
OFKTNode & operator=(const OFKTNode &)=delete
virtual OFKTNode * getParent()=0
Get the parent node.
virtual Eigen::Isometry3d computeLocalTransformation(double joint_value) const =0
Compute the local tranformation but do not save.
virtual bool updateWorldTransformationRequired() const =0
Indicates if an update of the world transformation is required.
virtual const std::string & getJointName() const =0
Get the joint name associated with the node.
virtual void computeAndStoreWorldTransformation()=0
Compute and store the nodes world transformation.
virtual const Eigen::Isometry3d & getWorldTransformation() const =0
Get the nodes world transformation.
virtual void setStaticTransformation(const Eigen::Isometry3d &static_tf)=0
Set the static transformation.