Public Member Functions | Private Attributes
AdvancedChainFkSolverVel_recursive Class Reference

#include <advanced_chainfksolver_recursive.hpp>

Inheritance diagram for AdvancedChainFkSolverVel_recursive:
Inheritance graph
[legend]

List of all members.

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)
 ~AdvancedChainFkSolverVel_recursive ()

Private Attributes

const KDL::Chainchain_
FrameVelVector_t segment_vel_

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

Definition at line 117 of file advanced_chainfksolver_recursive.cpp.

Definition at line 190 of file advanced_chainfksolver_recursive.cpp.


Member Function Documentation

Parameters:
seg_idxIndex of the segment starting with 0.
Returns:
The reference frame of the segment.

Definition at line 177 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.


Member Data Documentation

Definition at line 93 of file advanced_chainfksolver_recursive.hpp.

Definition at line 94 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 Jun 6 2019 21:19:14