Public Member Functions | Private Attributes | List of all members
AdvancedChainFkSolverVel_recursive Class Reference

#include <advanced_chainfksolver_recursive.hpp>

Inheritance diagram for AdvancedChainFkSolverVel_recursive:
Inheritance graph
[legend]

Public Member Functions

 AdvancedChainFkSolverVel_recursive (const KDL::Chain &chain)
 
KDL::FrameVel getFrameVelAtSegment (uint16_t seg_idx) const
 
virtual int JntToCart (const KDL::JntArrayVel &q_in, KDL::FrameVel &out, int seg_nr=-1)
 
virtual int JntToCart (const KDL::JntArrayVel &q_in, std::vector< KDL::FrameVel > &out, int segmentNr=-1)
 
virtual void updateInternalDataStructures ()
 
 ~AdvancedChainFkSolverVel_recursive ()
 
- Public Member Functions inherited from KDL::ChainFkSolverVel
virtual int JntToCart (const JntArrayVel &q_in, std::vector< KDL::FrameVel > &out, int segmentNr=-1)=0
 
virtual ~ChainFkSolverVel ()
 
- Public Member Functions inherited from KDL::SolverI
virtual int getError () const
 
 SolverI ()
 
virtual const char * strError (const int error) const
 
virtual ~SolverI ()
 

Private Attributes

const KDL::Chainchain_
 
FrameVelVector_t segment_vel_
 

Additional Inherited Members

- Public Attributes inherited from KDL::SolverI
 E_DEGRADED
 
 E_MAX_ITERATIONS_EXCEEDED
 
 E_NO_CONVERGE
 
 E_NOERROR
 
 E_NOT_IMPLEMENTED
 
 E_NOT_UP_TO_DATE
 
 E_OUT_OF_RANGE
 
 E_SIZE_MISMATCH
 
 E_SVD_FAILED
 
 E_UNDEFINED
 
- Protected Attributes inherited from KDL::SolverI
int error
 

Detailed Description

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

Definition at line 71 of file advanced_chainfksolver_recursive.hpp.

Constructor & Destructor Documentation

AdvancedChainFkSolverVel_recursive::AdvancedChainFkSolverVel_recursive ( const KDL::Chain chain)

Definition at line 117 of file advanced_chainfksolver_recursive.cpp.

AdvancedChainFkSolverVel_recursive::~AdvancedChainFkSolverVel_recursive ( )

Definition at line 237 of file advanced_chainfksolver_recursive.cpp.

Member Function Documentation

KDL::FrameVel AdvancedChainFkSolverVel_recursive::getFrameVelAtSegment ( uint16_t  seg_idx) const
Parameters
seg_idxIndex of the segment starting with 0.
Returns
The reference frame of the segment.

Definition at line 224 of file advanced_chainfksolver_recursive.cpp.

int AdvancedChainFkSolverVel_recursive::JntToCart ( const KDL::JntArrayVel q_in,
KDL::FrameVel out,
int  seg_nr = -1 
)
virtual
Parameters
q_inJoint states.
p_outThe output frame of the given segment or end-effector.
seg_nrThe max. segment nr until calculation should stop.
Returns
An error code (0 == success)

Calculates the cartesion velocities given to the joints and joint velocities array. This special implementation ensures that the velocities are stored in a vector so it is not necessary to call the method for each segment again and again.

Implements KDL::ChainFkSolverVel.

Definition at line 127 of file advanced_chainfksolver_recursive.cpp.

int AdvancedChainFkSolverVel_recursive::JntToCart ( const KDL::JntArrayVel q_in,
std::vector< KDL::FrameVel > &  out,
int  segmentNr = -1 
)
virtual

Definition at line 176 of file advanced_chainfksolver_recursive.cpp.

virtual void AdvancedChainFkSolverVel_recursive::updateInternalDataStructures ( )
inlinevirtual

Implements KDL::ChainFkSolverVel.

Definition at line 91 of file advanced_chainfksolver_recursive.hpp.

Member Data Documentation

const KDL::Chain& AdvancedChainFkSolverVel_recursive::chain_
private

Definition at line 91 of file advanced_chainfksolver_recursive.hpp.

FrameVelVector_t AdvancedChainFkSolverVel_recursive::segment_vel_
private

Definition at line 95 of file advanced_chainfksolver_recursive.hpp.


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


cob_obstacle_distance
Author(s): Marco Bezzon
autogenerated on Thu Apr 8 2021 02:39:47