Public Member Functions | Protected Attributes | Friends | List of all members
tesseract_scene_graph::OFKTBaseNode Class Reference

#include <ofkt_nodes.h>

Inheritance diagram for tesseract_scene_graph::OFKTBaseNode:
Inheritance graph
[legend]

Public Member Functions

void addChild (OFKTNode *node) override
 Add a child node. More...
 
void computeAndStoreWorldTransformation () override
 Compute and store the nodes world transformation. More...
 
Eigen::Isometry3d computeLocalTransformation (double joint_value) const override
 Compute the local tranformation but do not save. 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...
 
double getJointValue () const override
 Get the current joint value. 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 OFKTNodegetParent () const override
 Get the parent node (const) More...
 
OFKTNodegetParent () 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...
 
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...
 
bool updateWorldTransformationRequired () const override
 Indicates if an update of the world transformation is required. More...
 
- Public Member Functions inherited from tesseract_scene_graph::OFKTNode
virtual void computeAndStoreLocalTransformation ()=0
 Compute and save the local transformation 'L = S * J(Joint Value)'. More...
 
 OFKTNode ()=default
 
 OFKTNode (const OFKTNode &)=delete
 
 OFKTNode (OFKTNode &&)=delete
 
OFKTNodeoperator= (const OFKTNode &)=delete
 
OFKTNodeoperator= (OFKTNode &&)=delete
 
virtual ~OFKTNode ()=default
 

Protected Attributes

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) }
 
OFKTNodeparent_ { 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() }
 

Friends

class OFKTStateSolver
 

Additional Inherited Members

- Public Types inherited from tesseract_scene_graph::OFKTNode
using ConstPtr = std::shared_ptr< const OFKTNode >
 
using Ptr = std::shared_ptr< OFKTNode >
 
using UPtr = std::unique_ptr< OFKTNode >
 

Detailed Description

Definition at line 41 of file ofkt_nodes.h.

Constructor & Destructor Documentation

◆ OFKTBaseNode() [1/2]

tesseract_scene_graph::OFKTBaseNode::OFKTBaseNode ( JointType  type,
OFKTNode parent,
std::string  link_name 
)

Definition at line 41 of file ofkt_nodes.cpp.

◆ OFKTBaseNode() [2/2]

tesseract_scene_graph::OFKTBaseNode::OFKTBaseNode ( JointType  type,
OFKTNode parent,
std::string  link_name,
std::string  joint_name,
const Eigen::Isometry3d &  static_tf 
)

Definition at line 46 of file ofkt_nodes.cpp.

Member Function Documentation

◆ addChild()

void tesseract_scene_graph::OFKTBaseNode::addChild ( OFKTNode node)
overridevirtual

Add a child node.

Parameters
nodeThe node which is a child of this node

Implements tesseract_scene_graph::OFKTNode.

Definition at line 112 of file ofkt_nodes.cpp.

◆ computeAndStoreWorldTransformation()

void tesseract_scene_graph::OFKTBaseNode::computeAndStoreWorldTransformation ( )
overridevirtual

Compute and store the nodes world transformation.

This should reset the flag such that updateWorldTransformationRequired() returns false

Implements tesseract_scene_graph::OFKTNode.

Reimplemented in tesseract_scene_graph::OFKTRootNode.

Definition at line 102 of file ofkt_nodes.cpp.

◆ computeLocalTransformation()

Eigen::Isometry3d tesseract_scene_graph::OFKTBaseNode::computeLocalTransformation ( double  joint_value) const
overridevirtual

Compute the local tranformation but do not save.

This provides a const method for computing the local transform.

Parameters
joint_valueThe joint value for calculating the local transformation
Returns
The local transformation for the provided joint value

Implements tesseract_scene_graph::OFKTNode.

Reimplemented in tesseract_scene_graph::OFKTPrismaticNode, tesseract_scene_graph::OFKTContinuousNode, tesseract_scene_graph::OFKTRevoluteNode, tesseract_scene_graph::OFKTFloatingNode, tesseract_scene_graph::OFKTFixedNode, and tesseract_scene_graph::OFKTRootNode.

Definition at line 96 of file ofkt_nodes.cpp.

◆ getChildren() [1/2]

const std::vector<const OFKTNode*>& tesseract_scene_graph::OFKTBaseNode::getChildren ( ) const
overridevirtual

Get a vector of child nodes associated with this node (Const)

Returns
A vector of child nodes

Implements tesseract_scene_graph::OFKTNode.

◆ getChildren() [2/2]

const std::vector< const OFKTNode * > & tesseract_scene_graph::OFKTBaseNode::getChildren ( )
overridevirtual

Get a vector of child nodes associated with this node.

Returns
A vector of child nodes

Implements tesseract_scene_graph::OFKTNode.

Definition at line 124 of file ofkt_nodes.cpp.

◆ getJointName()

const std::string & tesseract_scene_graph::OFKTBaseNode::getJointName ( ) const
overridevirtual

Get the joint name associated with the node.

Returns
The link name

Implements tesseract_scene_graph::OFKTNode.

Definition at line 71 of file ofkt_nodes.cpp.

◆ getJointValue()

double tesseract_scene_graph::OFKTBaseNode::getJointValue ( ) const
overridevirtual

Get the current joint value.

Returns
The current joint value

Implements tesseract_scene_graph::OFKTNode.

Reimplemented in tesseract_scene_graph::OFKTFloatingNode, and tesseract_scene_graph::OFKTFixedNode.

Definition at line 82 of file ofkt_nodes.cpp.

◆ getLinkName()

const std::string & tesseract_scene_graph::OFKTBaseNode::getLinkName ( ) const
overridevirtual

Get the link name associated with the node.

Returns
The link name

Implements tesseract_scene_graph::OFKTNode.

Definition at line 70 of file ofkt_nodes.cpp.

◆ getLocalTransformation()

const Eigen::Isometry3d & tesseract_scene_graph::OFKTBaseNode::getLocalTransformation ( ) const
overridevirtual

Get the local transformation: 'L = S * J'.

Returns
The nodes local transformation

Implements tesseract_scene_graph::OFKTNode.

Definition at line 94 of file ofkt_nodes.cpp.

◆ getLocalTwist()

Eigen::Matrix< double, 6, 1 > tesseract_scene_graph::OFKTBaseNode::getLocalTwist ( ) const
overridevirtual

Return the twist of the node in its local frame.

Returns
The node twist

Implements tesseract_scene_graph::OFKTNode.

Definition at line 110 of file ofkt_nodes.cpp.

◆ getParent() [1/2]

const OFKTNode* tesseract_scene_graph::OFKTBaseNode::getParent ( ) const
overridevirtual

Get the parent node (const)

Returns
The parent node

Implements tesseract_scene_graph::OFKTNode.

◆ getParent() [2/2]

const OFKTNode * tesseract_scene_graph::OFKTBaseNode::getParent ( )
overridevirtual

Get the parent node.

Returns
The parent node

Implements tesseract_scene_graph::OFKTNode.

Definition at line 67 of file ofkt_nodes.cpp.

◆ getStaticTransformation()

const Eigen::Isometry3d & tesseract_scene_graph::OFKTBaseNode::getStaticTransformation ( ) const
overridevirtual

Get the nodes static transformation.

Returns
The static transformation

Implements tesseract_scene_graph::OFKTNode.

Definition at line 93 of file ofkt_nodes.cpp.

◆ getType()

tesseract_scene_graph::JointType tesseract_scene_graph::OFKTBaseNode::getType ( ) const
overridevirtual

Get the type of joint associated with the node.

Returns
The Joint Type

Implements tesseract_scene_graph::OFKTNode.

Definition at line 60 of file ofkt_nodes.cpp.

◆ getWorldTransformation()

const Eigen::Isometry3d & tesseract_scene_graph::OFKTBaseNode::getWorldTransformation ( ) const
overridevirtual

Get the nodes world transformation.

Returns
The nodes world transformation

Implements tesseract_scene_graph::OFKTNode.

Definition at line 107 of file ofkt_nodes.cpp.

◆ hasJointValueChanged()

bool tesseract_scene_graph::OFKTBaseNode::hasJointValueChanged ( ) const
overridevirtual

Indicates that the joint value has changed and that local and world transformation need to be recomputed.

Returns
If true, local and world transformation need to be recompute

Implements tesseract_scene_graph::OFKTNode.

Definition at line 84 of file ofkt_nodes.cpp.

◆ removeChild()

void tesseract_scene_graph::OFKTBaseNode::removeChild ( const OFKTNode node)
overridevirtual

Remove a child node assiciated with this node.

Parameters
nodeThe child node to be removed

Implements tesseract_scene_graph::OFKTNode.

Definition at line 118 of file ofkt_nodes.cpp.

◆ setParent()

void tesseract_scene_graph::OFKTBaseNode::setParent ( OFKTNode parent)
overridevirtual

Set the parent node.

This should indicate that updateWorldTransformationRequired() = true

Parameters
parentThe parent node

Implements tesseract_scene_graph::OFKTNode.

Reimplemented in tesseract_scene_graph::OFKTRootNode.

Definition at line 62 of file ofkt_nodes.cpp.

◆ setStaticTransformation()

void tesseract_scene_graph::OFKTBaseNode::setStaticTransformation ( const Eigen::Isometry3d &  static_tf)
overridevirtual

Set the static transformation.

This should recompute the local transformation and updateWorldTransformationRequired() = true.

Parameters
static_tfThe new static transformation

Implements tesseract_scene_graph::OFKTNode.

Reimplemented in tesseract_scene_graph::OFKTFloatingNode, tesseract_scene_graph::OFKTFixedNode, and tesseract_scene_graph::OFKTRootNode.

Definition at line 86 of file ofkt_nodes.cpp.

◆ storeJointValue()

void tesseract_scene_graph::OFKTBaseNode::storeJointValue ( double  joint_value)
overridevirtual

Set the nodes joint value if it has one.

This should indicate hasJointValueChanged() = true

Parameters
joint_valueThe joint value

Implements tesseract_scene_graph::OFKTNode.

Reimplemented in tesseract_scene_graph::OFKTRevoluteNode, tesseract_scene_graph::OFKTFloatingNode, tesseract_scene_graph::OFKTFixedNode, and tesseract_scene_graph::OFKTRootNode.

Definition at line 73 of file ofkt_nodes.cpp.

◆ updateWorldTransformationRequired()

bool tesseract_scene_graph::OFKTBaseNode::updateWorldTransformationRequired ( ) const
overridevirtual

Indicates if an update of the world transformation is required.

This should get set to true when either of the following happen.

Note: setJointValue() is not handle here because that is captured by hasJointValueChanged()

Returns
If true, the world transformation need to be recalculated.

Implements tesseract_scene_graph::OFKTNode.

Reimplemented in tesseract_scene_graph::OFKTRootNode.

Definition at line 108 of file ofkt_nodes.cpp.

Friends And Related Function Documentation

◆ OFKTStateSolver

friend class OFKTStateSolver
friend

Definition at line 107 of file ofkt_nodes.h.

Member Data Documentation

◆ children_

std::vector<OFKTNode*> tesseract_scene_graph::OFKTBaseNode::children_
protected

Definition at line 102 of file ofkt_nodes.h.

◆ children_const_

std::vector<const OFKTNode*> tesseract_scene_graph::OFKTBaseNode::children_const_
protected

Definition at line 103 of file ofkt_nodes.h.

◆ joint_name_

std::string tesseract_scene_graph::OFKTBaseNode::joint_name_
protected

Definition at line 92 of file ofkt_nodes.h.

◆ joint_tf_

Eigen::Isometry3d tesseract_scene_graph::OFKTBaseNode::joint_tf_ { Eigen::Isometry3d::Identity() }
protected

Definition at line 94 of file ofkt_nodes.h.

◆ joint_value_

double tesseract_scene_graph::OFKTBaseNode::joint_value_ { 0 }
protected

Definition at line 99 of file ofkt_nodes.h.

◆ joint_value_changed_

bool tesseract_scene_graph::OFKTBaseNode::joint_value_changed_ { false }
protected

Definition at line 100 of file ofkt_nodes.h.

◆ link_name_

std::string tesseract_scene_graph::OFKTBaseNode::link_name_
protected

Definition at line 91 of file ofkt_nodes.h.

◆ local_tf_

Eigen::Isometry3d tesseract_scene_graph::OFKTBaseNode::local_tf_ { Eigen::Isometry3d::Identity() }
protected

Definition at line 95 of file ofkt_nodes.h.

◆ local_twist_

Eigen::Matrix<double, 6, 1> tesseract_scene_graph::OFKTBaseNode::local_twist_ { Eigen::VectorXd::Zero(6) }
protected

Definition at line 97 of file ofkt_nodes.h.

◆ parent_

OFKTNode* tesseract_scene_graph::OFKTBaseNode::parent_ { nullptr }
protected

Definition at line 90 of file ofkt_nodes.h.

◆ static_tf_

Eigen::Isometry3d tesseract_scene_graph::OFKTBaseNode::static_tf_ { Eigen::Isometry3d::Identity() }
protected

Definition at line 93 of file ofkt_nodes.h.

◆ type_

tesseract_scene_graph::JointType tesseract_scene_graph::OFKTBaseNode::type_
protected

Definition at line 89 of file ofkt_nodes.h.

◆ update_world_required_

bool tesseract_scene_graph::OFKTBaseNode::update_world_required_ { true }
protected

Definition at line 105 of file ofkt_nodes.h.

◆ world_tf_

Eigen::Isometry3d tesseract_scene_graph::OFKTBaseNode::world_tf_ { Eigen::Isometry3d::Identity() }
protected

Definition at line 96 of file ofkt_nodes.h.


The documentation for this class was generated from the following files:


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