Public Member Functions | Private Attributes
KDL::ChainFkSolverPos_recursive Class Reference

#include <chainfksolverpos_recursive.hpp>

Inheritance diagram for KDL::ChainFkSolverPos_recursive:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 ChainFkSolverPos_recursive (const Chain &chain)
virtual int JntToCart (const JntArray &q_in, Frame &p_out, int segmentNr=-1)
 ~ChainFkSolverPos_recursive ()

Private Attributes

const Chain chain

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

Definition at line 28 of file chainfksolverpos_recursive.cpp.

Definition at line 61 of file chainfksolverpos_recursive.cpp.


Member Function Documentation

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 33 of file chainfksolverpos_recursive.cpp.


Member Data Documentation

Definition at line 45 of file chainfksolverpos_recursive.hpp.


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


orocos_kdl
Author(s):
autogenerated on Wed Aug 26 2015 15:14:15