Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
ofkt_nodes.h
Go to the documentation of this file.
1
31#ifndef TESSERACT_STATE_SOLVER_OFKT_NODES_H
32#define TESSERACT_STATE_SOLVER_OFKT_NODES_H
33
35
37{
38/*********************************************************************/
39/*************************** BASE NODE *******************************/
40/*********************************************************************/
41class OFKTBaseNode : public OFKTNode
42{
43public:
44 // LCOV_EXCL_START
45 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
46 // LCOV_EXCL_STOP
47
48 OFKTBaseNode(tesseract_scene_graph::JointType type, OFKTNode* parent, std::string link_name);
49
51 OFKTNode* parent,
52 std::string link_name,
53 std::string joint_name,
54 const Eigen::Isometry3d& static_tf);
55
56 JointType getType() const override;
57
58 void setParent(OFKTNode* parent) override;
59 OFKTNode* getParent() override;
60 const OFKTNode* getParent() const override;
61
62 const std::string& getLinkName() const override;
63 const std::string& getJointName() const override;
64
65 void storeJointValue(double joint_value) override;
66
67 double getJointValue() const override;
68
69 bool hasJointValueChanged() const override;
70
71 void setStaticTransformation(Eigen::Isometry3d static_tf) override;
72
73 const Eigen::Isometry3d& getStaticTransformation() const override;
74 const Eigen::Isometry3d& getLocalTransformation() const override;
75 Eigen::Isometry3d computeLocalTransformation(double joint_value) const override;
76
78 const Eigen::Isometry3d& getWorldTransformation() const override;
79 bool updateWorldTransformationRequired() const override;
80
81 Eigen::Matrix<double, 6, 1> getLocalTwist() const override;
82
83 void addChild(OFKTNode* node) override;
84 void removeChild(const OFKTNode* node) override;
85 std::vector<OFKTNode*>& getChildren() override;
86 const std::vector<const OFKTNode*>& getChildren() const override;
87
88protected:
90 OFKTNode* parent_{ nullptr };
91 std::string link_name_;
92 std::string joint_name_;
93 Eigen::Isometry3d static_tf_{ Eigen::Isometry3d::Identity() };
94 Eigen::Isometry3d joint_tf_{ Eigen::Isometry3d::Identity() };
95 Eigen::Isometry3d local_tf_{ Eigen::Isometry3d::Identity() };
96 Eigen::Isometry3d world_tf_{ Eigen::Isometry3d::Identity() };
97 Eigen::Matrix<double, 6, 1> local_twist_{ Eigen::VectorXd::Zero(6) };
98
99 double joint_value_{ 0 };
100 bool joint_value_changed_{ false };
101
102 std::vector<OFKTNode*> children_;
103 std::vector<const OFKTNode*> children_const_;
104
106
107 friend class OFKTStateSolver;
108};
109
110/*********************************************************************/
111/*************************** ROOT NODE *******************************/
112/*********************************************************************/
114{
115public:
116 // LCOV_EXCL_START
117 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
118 // LCOV_EXCL_STOP
119
124 OFKTRootNode(std::string link_name);
125
126 void setParent(OFKTNode* parent) override;
127 void storeJointValue(double joint_value) override;
128 void setStaticTransformation(Eigen::Isometry3d static_tf) override;
131 bool updateWorldTransformationRequired() const override;
132
133 Eigen::Isometry3d computeLocalTransformation(double joint_value) const override;
134
135private:
136 friend class OFKTStateSolver;
137};
138
139/**********************************************************************/
140/*************************** FIXED NODE *******************************/
141/**********************************************************************/
143{
144public:
145 // LCOV_EXCL_START
146 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
147 // LCOV_EXCL_STOP
148
149 OFKTFixedNode(OFKTNode* parent, std::string link_name, std::string joint_name, const Eigen::Isometry3d& static_tf);
150
151 void storeJointValue(double joint_value) override;
152 double getJointValue() const override;
153 void setStaticTransformation(Eigen::Isometry3d static_tf) override;
155 Eigen::Isometry3d computeLocalTransformation(double joint_value) const override;
156
157private:
158 friend class OFKTStateSolver;
159};
160
161/*********************************************************************/
162/************************* REVOLUTE NODE *****************************/
163/*********************************************************************/
165{
166public:
167 // LCOV_EXCL_START
168 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
169 // LCOV_EXCL_STOP
170
172 std::string link_name,
173 std::string joint_name,
174 const Eigen::Isometry3d& static_tf,
175 const Eigen::Vector3d& axis);
176
177 void storeJointValue(double joint_value) override;
179 Eigen::Isometry3d computeLocalTransformation(double joint_value) const override;
180 const Eigen::Vector3d& getAxis() const;
181
182private:
183 Eigen::Vector3d axis_;
184
186
187 friend class OFKTStateSolver;
188};
189
190/*********************************************************************/
191/************************ CONTINUOUS NODE ****************************/
192/*********************************************************************/
194{
195public:
196 // LCOV_EXCL_START
197 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
198 // LCOV_EXCL_STOP
199
201 std::string link_name,
202 std::string joint_name,
203 const Eigen::Isometry3d& static_tf,
204 const Eigen::Vector3d& axis);
205
207 Eigen::Isometry3d computeLocalTransformation(double joint_value) const override;
208 const Eigen::Vector3d& getAxis() const;
209
210private:
211 Eigen::Vector3d axis_;
212
214
215 friend class OFKTStateSolver;
216};
217
218/*********************************************************************/
219/************************* PRISMATIC NODE ****************************/
220/*********************************************************************/
222{
223public:
224 // LCOV_EXCL_START
225 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
226 // LCOV_EXCL_STOP
227
229 std::string link_name,
230 std::string joint_name,
231 const Eigen::Isometry3d& static_tf,
232 const Eigen::Vector3d& axis);
233
235 Eigen::Isometry3d computeLocalTransformation(double joint_value) const override;
236 const Eigen::Vector3d& getAxis() const;
237
238private:
239 Eigen::Vector3d axis_;
240
242
243 friend class OFKTStateSolver;
244};
245} // namespace tesseract_scene_graph
246
247#endif // TESSERACT_STATE_SOLVER_OFKT_NODES_H
Definition: ofkt_nodes.h:42
void storeJointValue(double joint_value) override
Set the nodes joint value if it has one.
Definition: ofkt_nodes.cpp:72
void setStaticTransformation(Eigen::Isometry3d static_tf) override
Set the static transformation.
Definition: ofkt_nodes.cpp:85
double joint_value_
Definition: ofkt_nodes.h:99
void computeAndStoreWorldTransformation() override
Compute and store the nodes world transformation.
Definition: ofkt_nodes.cpp:101
std::vector< OFKTNode * > & getChildren() override
Get a vector of child nodes associated with this node.
Definition: ofkt_nodes.cpp:123
bool update_world_required_
Definition: ofkt_nodes.h:105
void setParent(OFKTNode *parent) override
Set the parent node.
Definition: ofkt_nodes.cpp:61
Eigen::Isometry3d static_tf_
Definition: ofkt_nodes.h:93
OFKTNode * parent_
Definition: ofkt_nodes.h:90
JointType getType() const override
Get the type of joint associated with the node.
Definition: ofkt_nodes.cpp:59
Eigen::Matrix< double, 6, 1 > local_twist_
Definition: ofkt_nodes.h:97
void addChild(OFKTNode *node) override
Add a child node.
Definition: ofkt_nodes.cpp:111
const Eigen::Isometry3d & getLocalTransformation() const override
Get the local transformation: 'L = S * J'.
Definition: ofkt_nodes.cpp:93
tesseract_scene_graph::JointType type_
Definition: ofkt_nodes.h:89
std::vector< const OFKTNode * > children_const_
Definition: ofkt_nodes.h:103
const std::string & getLinkName() const override
Get the link name associated with the node.
Definition: ofkt_nodes.cpp:69
const Eigen::Isometry3d & getWorldTransformation() const override
Get the nodes world transformation.
Definition: ofkt_nodes.cpp:106
bool hasJointValueChanged() const override
Indicates that the joint value has changed and that local and world transformation need to be recompu...
Definition: ofkt_nodes.cpp:83
double getJointValue() const override
Get the current joint value.
Definition: ofkt_nodes.cpp:81
Eigen::Isometry3d computeLocalTransformation(double joint_value) const override
Compute the local tranformation but do not save.
Definition: ofkt_nodes.cpp:95
const std::string & getJointName() const override
Get the joint name associated with the node.
Definition: ofkt_nodes.cpp:70
Eigen::Isometry3d local_tf_
Definition: ofkt_nodes.h:95
void removeChild(const OFKTNode *node) override
Remove a child node assiciated with this node.
Definition: ofkt_nodes.cpp:117
OFKTNode * getParent() override
Get the parent node.
Definition: ofkt_nodes.cpp:66
std::string link_name_
Definition: ofkt_nodes.h:91
Eigen::Isometry3d world_tf_
Definition: ofkt_nodes.h:96
bool updateWorldTransformationRequired() const override
Indicates if an update of the world transformation is required.
Definition: ofkt_nodes.cpp:107
bool joint_value_changed_
Definition: ofkt_nodes.h:100
const Eigen::Isometry3d & getStaticTransformation() const override
Get the nodes static transformation.
Definition: ofkt_nodes.cpp:92
Eigen::Matrix< double, 6, 1 > getLocalTwist() const override
Return the twist of the node in its local frame.
Definition: ofkt_nodes.cpp:109
std::string joint_name_
Definition: ofkt_nodes.h:92
Eigen::Isometry3d joint_tf_
Definition: ofkt_nodes.h:94
std::vector< OFKTNode * > children_
Definition: ofkt_nodes.h:102
Definition: ofkt_nodes.h:194
const Eigen::Vector3d & getAxis() const
Definition: ofkt_nodes.cpp:263
Eigen::Isometry3d computeLocalTransformation(double joint_value) const override
Compute the local tranformation but do not save.
Definition: ofkt_nodes.cpp:258
Eigen::Vector3d axis_
Definition: ofkt_nodes.h:211
void computeAndStoreLocalTransformation() override
Compute and save the local transformation 'L = S * J(Joint Value)'.
Definition: ofkt_nodes.cpp:256
void computeAndStoreLocalTransformationImpl()
Definition: ofkt_nodes.cpp:249
Definition: ofkt_nodes.h:143
void setStaticTransformation(Eigen::Isometry3d static_tf) override
Set the static transformation.
Definition: ofkt_nodes.cpp:180
void storeJointValue(double joint_value) override
Set the nodes joint value if it has one.
Definition: ofkt_nodes.cpp:173
double getJointValue() const override
Get the current joint value.
Definition: ofkt_nodes.cpp:178
void computeAndStoreLocalTransformation() override
Compute and save the local transformation 'L = S * J(Joint Value)'.
Definition: ofkt_nodes.cpp:187
Eigen::Isometry3d computeLocalTransformation(double joint_value) const override
Compute the local tranformation but do not save.
Definition: ofkt_nodes.cpp:189
The OFKT node is contains multiple trasformation which are described below.
Definition: ofkt_node.h:56
Definition: ofkt_nodes.h:222
void computeAndStoreLocalTransformation() override
Compute and save the local transformation 'L = S * J(Joint Value)'.
Definition: ofkt_nodes.cpp:292
Eigen::Isometry3d computeLocalTransformation(double joint_value) const override
Compute the local tranformation but do not save.
Definition: ofkt_nodes.cpp:294
void computeAndStoreLocalTransformationImpl()
Definition: ofkt_nodes.cpp:285
Eigen::Vector3d axis_
Definition: ofkt_nodes.h:239
const Eigen::Vector3d & getAxis() const
Definition: ofkt_nodes.cpp:299
Definition: ofkt_nodes.h:165
void computeAndStoreLocalTransformation() override
Compute and save the local transformation 'L = S * J(Joint Value)'.
Definition: ofkt_nodes.cpp:220
void storeJointValue(double joint_value) override
Set the nodes joint value if it has one.
Definition: ofkt_nodes.cpp:211
void computeAndStoreLocalTransformationImpl()
Definition: ofkt_nodes.cpp:213
Eigen::Vector3d axis_
Definition: ofkt_nodes.h:183
Eigen::Isometry3d computeLocalTransformation(double joint_value) const override
Compute the local tranformation but do not save.
Definition: ofkt_nodes.cpp:222
const Eigen::Vector3d & getAxis() const
Definition: ofkt_nodes.cpp:227
Definition: ofkt_nodes.h:114
Eigen::Isometry3d computeLocalTransformation(double joint_value) const override
Compute the local tranformation but do not save.
Definition: ofkt_nodes.cpp:155
void setStaticTransformation(Eigen::Isometry3d static_tf) override
Set the static transformation.
Definition: ofkt_nodes.cpp:146
void computeAndStoreLocalTransformation() override
Compute and save the local transformation 'L = S * J(Joint Value)'.
Definition: ofkt_nodes.cpp:151
void setParent(OFKTNode *parent) override
Set the parent node.
Definition: ofkt_nodes.cpp:136
bool updateWorldTransformationRequired() const override
Indicates if an update of the world transformation is required.
Definition: ofkt_nodes.cpp:153
void storeJointValue(double joint_value) override
Set the nodes joint value if it has one.
Definition: ofkt_nodes.cpp:141
void computeAndStoreWorldTransformation() override
Compute and store the nodes world transformation.
Definition: ofkt_nodes.cpp:152
An implementation of the Optimized Forward Kinematic Tree as a stat solver.
Definition: ofkt_state_solver.h:55
Definition: graph.h:82
JointType
Definition: joint.h:270
A implementation of the Optimized Forward Kinematic Tree Node.
mCollisionCheckConfig contact_request type
Definition: tesseract_environment_collision.cpp:103
joint_1 mimic joint_name
Definition: tesseract_scene_graph_joint_unit.cpp:163
object axis
Definition: tesseract_scene_graph_serialization_unit.cpp:81