#include <ofkt_nodes.h>
Public Member Functions | |
void | computeAndStoreLocalTransformation () override |
Compute and save the local transformation 'L = S * J(Joint Value)'. More... | |
Eigen::Isometry3d | computeLocalTransformation (double joint_value) const override |
Compute the local tranformation but do not save. More... | |
double | getJointValue () const override |
Get the current joint value. More... | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | OFKTFloatingNode (OFKTNode *parent, std::string link_name, std::string joint_name, const Eigen::Isometry3d &static_tf) |
void | setStaticTransformation (const Eigen::Isometry3d &static_tf) override |
Set the static transformation. More... | |
void | storeJointValue (double joint_value) override |
Set the nodes joint value if it has one. More... | |
![]() | |
void | addChild (OFKTNode *node) override |
Add a child node. More... | |
void | computeAndStoreWorldTransformation () override |
Compute and store the nodes world transformation. More... | |
const std::vector< const OFKTNode * > & | getChildren () const override |
Get a vector of child nodes associated with this node (Const) More... | |
std::vector< OFKTNode * > & | getChildren () override |
Get a vector of child nodes associated with this node. More... | |
const std::string & | getJointName () const override |
Get the joint name associated with the node. More... | |
const std::string & | getLinkName () const override |
Get the link name associated with the node. More... | |
const Eigen::Isometry3d & | getLocalTransformation () const override |
Get the local transformation: 'L = S * J'. More... | |
Eigen::Matrix< double, 6, 1 > | getLocalTwist () const override |
Return the twist of the node in its local frame. More... | |
const OFKTNode * | getParent () const override |
Get the parent node (const) More... | |
OFKTNode * | getParent () override |
Get the parent node. More... | |
const Eigen::Isometry3d & | getStaticTransformation () const override |
Get the nodes static transformation. More... | |
JointType | getType () const override |
Get the type of joint associated with the node. More... | |
const Eigen::Isometry3d & | getWorldTransformation () const override |
Get the nodes world transformation. More... | |
bool | hasJointValueChanged () const override |
Indicates that the joint value has changed and that local and world transformation need to be recomputed. More... | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | OFKTBaseNode (JointType type, OFKTNode *parent, std::string link_name) |
OFKTBaseNode (JointType type, OFKTNode *parent, std::string link_name, std::string joint_name, const Eigen::Isometry3d &static_tf) | |
void | removeChild (const OFKTNode *node) override |
Remove a child node assiciated with this node. More... | |
void | setParent (OFKTNode *parent) override |
Set the parent node. More... | |
bool | updateWorldTransformationRequired () const override |
Indicates if an update of the world transformation is required. More... | |
![]() | |
OFKTNode ()=default | |
OFKTNode (const OFKTNode &)=delete | |
OFKTNode (OFKTNode &&)=delete | |
OFKTNode & | operator= (const OFKTNode &)=delete |
OFKTNode & | operator= (OFKTNode &&)=delete |
virtual | ~OFKTNode ()=default |
Friends | |
class | OFKTStateSolver |
Additional Inherited Members | |
![]() | |
using | ConstPtr = std::shared_ptr< const OFKTNode > |
using | Ptr = std::shared_ptr< OFKTNode > |
using | UPtr = std::unique_ptr< OFKTNode > |
![]() | |
std::vector< OFKTNode * > | children_ |
std::vector< const OFKTNode * > | children_const_ |
std::string | joint_name_ |
Eigen::Isometry3d | joint_tf_ { Eigen::Isometry3d::Identity() } |
double | joint_value_ { 0 } |
bool | joint_value_changed_ { false } |
std::string | link_name_ |
Eigen::Isometry3d | local_tf_ { Eigen::Isometry3d::Identity() } |
Eigen::Matrix< double, 6, 1 > | local_twist_ { Eigen::VectorXd::Zero(6) } |
OFKTNode * | parent_ { nullptr } |
Eigen::Isometry3d | static_tf_ { Eigen::Isometry3d::Identity() } |
tesseract_scene_graph::JointType | type_ |
bool | update_world_required_ { true } |
Eigen::Isometry3d | world_tf_ { Eigen::Isometry3d::Identity() } |
Definition at line 164 of file ofkt_nodes.h.
tesseract_scene_graph::OFKTFloatingNode::OFKTFloatingNode | ( | OFKTNode * | parent, |
std::string | link_name, | ||
std::string | joint_name, | ||
const Eigen::Isometry3d & | static_tf | ||
) |
Definition at line 195 of file ofkt_nodes.cpp.
|
overridevirtual |
Compute and save the local transformation 'L = S * J(Joint Value)'.
This should reset the flag such that hasJointValueChanged() returns false
Implements tesseract_scene_graph::OFKTNode.
Definition at line 225 of file ofkt_nodes.cpp.
|
overridevirtual |
Compute the local tranformation but do not save.
This provides a const method for computing the local transform.
joint_value | The joint value for calculating the local transformation |
Reimplemented from tesseract_scene_graph::OFKTBaseNode.
Definition at line 227 of file ofkt_nodes.cpp.
|
overridevirtual |
Get the current joint value.
Reimplemented from tesseract_scene_graph::OFKTBaseNode.
Definition at line 213 of file ofkt_nodes.cpp.
|
overridevirtual |
Set the static transformation.
This should recompute the local transformation and updateWorldTransformationRequired() = true.
static_tf | The new static transformation |
Reimplemented from tesseract_scene_graph::OFKTBaseNode.
Definition at line 218 of file ofkt_nodes.cpp.
|
overridevirtual |
Set the nodes joint value if it has one.
This should indicate hasJointValueChanged() = true
joint_value | The joint value |
Reimplemented from tesseract_scene_graph::OFKTBaseNode.
Definition at line 208 of file ofkt_nodes.cpp.
|
friend |
Definition at line 180 of file ofkt_nodes.h.