Public Member Functions | Private Member Functions | Private Attributes | Friends | List of all members
tesseract_scene_graph::OFKTRevoluteNode Class Reference

#include <ofkt_nodes.h>

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

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...
 
const Eigen::Vector3d & getAxis () const
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW OFKTRevoluteNode (OFKTNode *parent, std::string link_name, std::string joint_name, const Eigen::Isometry3d &static_tf, const Eigen::Vector3d &axis)
 
void storeJointValue (double joint_value) override
 Set the nodes joint value if it has one. More...
 
- Public Member Functions inherited from tesseract_scene_graph::OFKTBaseNode
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...
 
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...
 
bool updateWorldTransformationRequired () const override
 Indicates if an update of the world transformation is required. More...
 
- Public Member Functions inherited from tesseract_scene_graph::OFKTNode
 OFKTNode ()=default
 
 OFKTNode (const OFKTNode &)=delete
 
 OFKTNode (OFKTNode &&)=delete
 
OFKTNodeoperator= (const OFKTNode &)=delete
 
OFKTNodeoperator= (OFKTNode &&)=delete
 
virtual ~OFKTNode ()=default
 

Private Member Functions

void computeAndStoreLocalTransformationImpl ()
 

Private Attributes

Eigen::Vector3d axis_
 

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 >
 
- Protected Attributes inherited from tesseract_scene_graph::OFKTBaseNode
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() }
 

Detailed Description

Definition at line 186 of file ofkt_nodes.h.

Constructor & Destructor Documentation

◆ OFKTRevoluteNode()

tesseract_scene_graph::OFKTRevoluteNode::OFKTRevoluteNode ( OFKTNode parent,
std::string  link_name,
std::string  joint_name,
const Eigen::Isometry3d &  static_tf,
const Eigen::Vector3d &  axis 
)

Definition at line 232 of file ofkt_nodes.cpp.

Member Function Documentation

◆ computeAndStoreLocalTransformation()

void tesseract_scene_graph::OFKTRevoluteNode::computeAndStoreLocalTransformation ( )
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 258 of file ofkt_nodes.cpp.

◆ computeAndStoreLocalTransformationImpl()

void tesseract_scene_graph::OFKTRevoluteNode::computeAndStoreLocalTransformationImpl ( )
private

Definition at line 251 of file ofkt_nodes.cpp.

◆ computeLocalTransformation()

Eigen::Isometry3d tesseract_scene_graph::OFKTRevoluteNode::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

Reimplemented from tesseract_scene_graph::OFKTBaseNode.

Definition at line 260 of file ofkt_nodes.cpp.

◆ getAxis()

const Eigen::Vector3d & tesseract_scene_graph::OFKTRevoluteNode::getAxis ( ) const

Definition at line 265 of file ofkt_nodes.cpp.

◆ storeJointValue()

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

Set the nodes joint value if it has one.

This should indicate hasJointValueChanged() = true

Parameters
joint_valueThe joint value

Reimplemented from tesseract_scene_graph::OFKTBaseNode.

Definition at line 249 of file ofkt_nodes.cpp.

Friends And Related Function Documentation

◆ OFKTStateSolver

friend class OFKTStateSolver
friend

Definition at line 209 of file ofkt_nodes.h.

Member Data Documentation

◆ axis_

Eigen::Vector3d tesseract_scene_graph::OFKTRevoluteNode::axis_
private

Definition at line 205 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