ofkt_node.h
Go to the documentation of this file.
1 
31 #ifndef TESSERACT_STATE_SOLVER_OFKT_NODE_H
32 #define TESSERACT_STATE_SOLVER_OFKT_NODE_H
33 
36 #include <Eigen/Geometry>
37 #include <memory>
38 #include <string>
39 #include <vector>
41 
43 
44 namespace tesseract_scene_graph
45 {
55 class OFKTNode
56 {
57 public:
58  // LCOV_EXCL_START
59  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
60  // LCOV_EXCL_STOP
61 
62  using UPtr = std::unique_ptr<OFKTNode>;
63  using Ptr = std::shared_ptr<OFKTNode>;
64  using ConstPtr = std::shared_ptr<const OFKTNode>;
65 
66  OFKTNode() = default;
67  virtual ~OFKTNode() = default;
68  OFKTNode(const OFKTNode&) = delete;
69  OFKTNode& operator=(const OFKTNode&) = delete;
70  OFKTNode(OFKTNode&&) = delete;
71  OFKTNode& operator=(OFKTNode&&) = delete;
72 
77  virtual JointType getType() const = 0;
78 
86  virtual void setParent(OFKTNode* parent) = 0;
87 
92  virtual OFKTNode* getParent() = 0;
93 
98  virtual const OFKTNode* getParent() const = 0;
99 
104  virtual const std::string& getLinkName() const = 0;
105 
110  virtual const std::string& getJointName() const = 0;
111 
119  virtual void storeJointValue(double joint_value) = 0;
120 
125  virtual double getJointValue() const = 0;
126 
131  virtual bool hasJointValueChanged() const = 0;
132 
140  virtual void setStaticTransformation(const Eigen::Isometry3d& static_tf) = 0;
141 
146  virtual const Eigen::Isometry3d& getStaticTransformation() const = 0;
147 
153  virtual void computeAndStoreLocalTransformation() = 0;
154 
159  virtual const Eigen::Isometry3d& getLocalTransformation() const = 0;
160 
169  virtual Eigen::Isometry3d computeLocalTransformation(double joint_value) const = 0;
170 
176  virtual void computeAndStoreWorldTransformation() = 0;
177 
182  virtual const Eigen::Isometry3d& getWorldTransformation() const = 0;
183 
194  virtual bool updateWorldTransformationRequired() const = 0;
195 
200  virtual Eigen::Matrix<double, 6, 1> getLocalTwist() const = 0;
201 
206  virtual void addChild(OFKTNode* node) = 0;
207 
212  virtual void removeChild(const OFKTNode* node) = 0;
213 
218  virtual std::vector<OFKTNode*>& getChildren() = 0;
219 
224  virtual const std::vector<const OFKTNode*>& getChildren() const = 0;
225 };
226 } // namespace tesseract_scene_graph
227 
228 #endif // TESSERACT_STATE_SOLVER_OFKT_NODE_H
tesseract_scene_graph::OFKTNode::Ptr
std::shared_ptr< OFKTNode > Ptr
Definition: ofkt_node.h:63
tesseract_scene_graph::OFKTNode::getLocalTwist
virtual Eigen::Matrix< double, 6, 1 > getLocalTwist() const =0
Return the twist of the node in its local frame.
tesseract_scene_graph::OFKTNode::storeJointValue
virtual void storeJointValue(double joint_value)=0
Set the nodes joint value if it has one.
tesseract_scene_graph::OFKTNode::getJointValue
virtual double getJointValue() const =0
Get the current joint value.
tesseract_scene_graph::OFKTNode::~OFKTNode
virtual ~OFKTNode()=default
tesseract_scene_graph::OFKTNode::OFKTNode
OFKTNode()=default
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_scene_graph::OFKTNode::setParent
virtual void setParent(OFKTNode *parent)=0
Set the parent node.
tesseract_scene_graph::OFKTNode::ConstPtr
std::shared_ptr< const OFKTNode > ConstPtr
Definition: ofkt_node.h:64
tesseract_scene_graph::OFKTNode::getLinkName
virtual const std::string & getLinkName() const =0
Get the link name associated with the node.
tesseract_scene_graph::OFKTNode::getStaticTransformation
virtual const Eigen::Isometry3d & getStaticTransformation() const =0
Get the nodes static transformation.
tesseract_scene_graph::OFKTNode::getLocalTransformation
virtual const Eigen::Isometry3d & getLocalTransformation() const =0
Get the local transformation: 'L = S * J'.
tesseract_scene_graph::OFKTNode::UPtr
std::unique_ptr< OFKTNode > UPtr
Definition: ofkt_node.h:62
tesseract_scene_graph::OFKTNode::hasJointValueChanged
virtual bool hasJointValueChanged() const =0
Indicates that the joint value has changed and that local and world transformation need to be recompu...
tesseract_scene_graph::OFKTNode
The OFKT node is contains multiple trasformation which are described below.
Definition: ofkt_node.h:55
tesseract_scene_graph::OFKTNode::getType
virtual JointType getType() const =0
Get the type of joint associated with the node.
fwd.h
TESSERACT_COMMON_IGNORE_WARNINGS_POP
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
tesseract_scene_graph::OFKTNode::addChild
virtual void addChild(OFKTNode *node)=0
Add a child node.
tesseract_scene_graph::OFKTNode::computeAndStoreLocalTransformation
virtual void computeAndStoreLocalTransformation()=0
Compute and save the local transformation 'L = S * J(Joint Value)'.
tesseract_scene_graph::JointType
JointType
tesseract_scene_graph::OFKTNode::removeChild
virtual void removeChild(const OFKTNode *node)=0
Remove a child node assiciated with this node.
tesseract_scene_graph::OFKTNode::getChildren
virtual std::vector< OFKTNode * > & getChildren()=0
Get a vector of child nodes associated with this node.
tesseract_scene_graph::OFKTNode::operator=
OFKTNode & operator=(const OFKTNode &)=delete
tesseract_scene_graph::OFKTNode::getParent
virtual OFKTNode * getParent()=0
Get the parent node.
tesseract_scene_graph::OFKTNode::computeLocalTransformation
virtual Eigen::Isometry3d computeLocalTransformation(double joint_value) const =0
Compute the local tranformation but do not save.
tesseract_scene_graph::OFKTNode::updateWorldTransformationRequired
virtual bool updateWorldTransformationRequired() const =0
Indicates if an update of the world transformation is required.
macros.h
tesseract_scene_graph::OFKTNode::getJointName
virtual const std::string & getJointName() const =0
Get the joint name associated with the node.
tesseract_scene_graph
tesseract_scene_graph::OFKTNode::computeAndStoreWorldTransformation
virtual void computeAndStoreWorldTransformation()=0
Compute and store the nodes world transformation.
tesseract_scene_graph::OFKTNode::getWorldTransformation
virtual const Eigen::Isometry3d & getWorldTransformation() const =0
Get the nodes world transformation.
tesseract_scene_graph::OFKTNode::setStaticTransformation
virtual void setStaticTransformation(const Eigen::Isometry3d &static_tf)=0
Set the static transformation.


tesseract_state_solver
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:02:10