Blender  V3.3
Public Member Functions | List of all members
KDL::ChainFkSolverPos_recursive Class Reference

#include <chainfksolverpos_recursive.hpp>

Inheritance diagram for KDL::ChainFkSolverPos_recursive:
KDL::ChainFkSolverPos

Public Member Functions

 ChainFkSolverPos_recursive (const Chain &chain)
 
 ~ChainFkSolverPos_recursive ()
 
virtual int JntToCart (const JntArray &q_in, Frame &p_out, int segmentNr=-1)
 
- Public Member Functions inherited from KDL::ChainFkSolverPos
virtual ~ChainFkSolverPos ()
 

Detailed Description

Implementation of a recursive forward position kinematics algorithm to calculate the position transformation from joint space to Cartesian space of a general kinematic chain (KDL::Chain).

Definition at line 36 of file chainfksolverpos_recursive.hpp.

Constructor & Destructor Documentation

◆ ChainFkSolverPos_recursive()

KDL::ChainFkSolverPos_recursive::ChainFkSolverPos_recursive ( const Chain chain)

Definition at line 31 of file chainfksolverpos_recursive.cpp.

◆ ~ChainFkSolverPos_recursive()

KDL::ChainFkSolverPos_recursive::~ChainFkSolverPos_recursive ( )

Definition at line 59 of file chainfksolverpos_recursive.cpp.

Member Function Documentation

◆ JntToCart()

int KDL::ChainFkSolverPos_recursive::JntToCart ( const JntArray q_in,
Frame p_out,
int  segmentNr = -1 
)
virtual

Calculate forward position kinematics for a KDL::Chain, from joint coordinates to cartesian pose.

Parameters
q_ininput joint coordinates
p_outreference to output cartesian pose
Returns
if < 0 something went wrong

Implements KDL::ChainFkSolverPos.

Definition at line 36 of file chainfksolverpos_recursive.cpp.

References KDL::Segment::getJoint(), KDL::Joint::getNDof(), KDL::Chain::getNrOfJoints(), KDL::Chain::getNrOfSegments(), KDL::Chain::getSegment(), KDL::Frame::Identity(), KDL::Segment::pose(), and KDL::JntArray::rows().

Referenced by iTaSC::Distance::updateJacobian().


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