31#ifndef TESSERACT_STATE_SOLVER_OFKT_NODES_H 
   32#define TESSERACT_STATE_SOLVER_OFKT_NODES_H 
   45  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
   52               std::string link_name,
 
   54               const Eigen::Isometry3d& static_tf);
 
   86  const std::vector<const OFKTNode*>& 
getChildren() 
const override;
 
   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) };
 
  117  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
  146  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
  168  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
  172                   std::string link_name,
 
  174                   const Eigen::Isometry3d& static_tf,
 
  175                   const Eigen::Vector3d& 
axis);
 
  180  const Eigen::Vector3d& 
getAxis() 
const;
 
  197  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
  201                     std::string link_name,
 
  203                     const Eigen::Isometry3d& static_tf,
 
  204                     const Eigen::Vector3d& 
axis);
 
  208  const Eigen::Vector3d& 
getAxis() 
const;
 
  225  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
  229                    std::string link_name,
 
  231                    const Eigen::Isometry3d& static_tf,
 
  232                    const Eigen::Vector3d& 
axis);
 
  236  const Eigen::Vector3d& 
getAxis() 
const;
 
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
 
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