KDL  1.4.0
chainfksolvervel_recursive.hpp
Go to the documentation of this file.
1 // Copyright (C) 2007 Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
2 
3 // Version: 1.0
4 // Author: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
5 // Maintainer: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
6 // URL: http://www.orocos.org/kdl
7 
8 // This library is free software; you can redistribute it and/or
9 // modify it under the terms of the GNU Lesser General Public
10 // License as published by the Free Software Foundation; either
11 // version 2.1 of the License, or (at your option) any later version.
12 
13 // This library is distributed in the hope that it will be useful,
14 // but WITHOUT ANY WARRANTY; without even the implied warranty of
15 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
16 // Lesser General Public License for more details.
17 
18 // You should have received a copy of the GNU Lesser General Public
19 // License along with this library; if not, write to the Free Software
20 // Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
21 
22 #ifndef KDL_CHAIN_FKSOLVERVEL_RECURSIVE_HPP
23 #define KDL_CHAIN_FKSOLVERVEL_RECURSIVE_HPP
24 
25 #include "chainfksolver.hpp"
26 
27 namespace KDL
28 {
38  {
39  public:
42 
43  virtual int JntToCart(const JntArrayVel& q_in,FrameVel& out,int segmentNr=-1);
44  virtual int JntToCart(const JntArrayVel& q_in,std::vector<FrameVel>& out,int segmentNr=-1);
45  virtual void updateInternalDataStructures() {};
46  private:
47  const Chain& chain;
48  };
49 }
50 
51 #endif
KDL::ChainFkSolverVel_recursive::JntToCart
virtual int JntToCart(const JntArrayVel &q_in, FrameVel &out, int segmentNr=-1)
Calculate forward position and velocity kinematics, from joint coordinates to cartesian coordinates.
Definition: chainfksolvervel_recursive.cpp:36
KDL::ChainFkSolverVel_recursive::chain
const Chain & chain
Definition: chainfksolvervel_recursive.hpp:45
KDL::Segment::getJoint
const Joint & getJoint() const
Request the joint of the segment.
Definition: segment.hpp:118
KDL::ChainFkSolverVel
This abstract class encapsulates a solver for the forward velocity kinematics for a KDL::Chain.
Definition: chainfksolver.hpp:74
KDL
Definition: articulatedbodyinertia.cpp:28
KDL::Chain::getNrOfSegments
unsigned int getNrOfSegments() const
Request the total number of segments in the chain.
Definition: chain.hpp:76
chainfksolver.hpp
KDL::SolverI::E_OUT_OF_RANGE
@ E_OUT_OF_RANGE
Requested index out of range.
Definition: solveri.hpp:103
KDL::JntArray::rows
unsigned int rows() const
Returns the number of rows (size) of the array.
Definition: jntarray.cpp:72
KDL::Chain::getSegment
const Segment & getSegment(unsigned int nr) const
Request the nr'd segment of the chain.
Definition: chain.cpp:68
KDL::SolverI::E_SIZE_MISMATCH
@ E_SIZE_MISMATCH
Input size does not match internal state.
Definition: solveri.hpp:99
KDL::Segment::pose
Frame pose(const double &q) const
Request the pose of the segment, given the joint position q.
Definition: segment.cpp:57
KDL::ChainFkSolverVel_recursive
Implementation of a recursive forward position and velocity kinematics algorithm to calculate the pos...
Definition: chainfksolvervel_recursive.hpp:38
KDL::Segment::twist
Twist twist(const double &q, const double &qdot) const
Request the 6D-velocity of the tip of the segment, given the joint position q and the joint velocity ...
Definition: segment.cpp:62
KDL::Joint::None
@ None
Definition: joint.hpp:47
KDL::ChainFkSolverVel_recursive::~ChainFkSolverVel_recursive
~ChainFkSolverVel_recursive()
Definition: chainfksolvervel_recursive.cpp:32
KDL::JntArrayVel
Definition: jntarrayvel.hpp:46
KDL::FrameVel::Identity
static IMETHOD FrameVel Identity()
Definition: framevel.inl:28
chainfksolvervel_recursive.hpp
KDL::JntArrayVel::qdot
JntArray qdot
Definition: jntarrayvel.hpp:49
KDL::ChainFkSolverVel_recursive::updateInternalDataStructures
virtual void updateInternalDataStructures()
Update the internal data structures.
Definition: chainfksolvervel_recursive.hpp:45
KDL::FrameVel
Definition: framevel.hpp:204
KDL::Joint::getType
const JointType & getType() const
Request the type of the joint.
Definition: joint.hpp:159
KDL::ChainFkSolverVel_recursive::ChainFkSolverVel_recursive
ChainFkSolverVel_recursive(const Chain &chain)
Definition: chainfksolvervel_recursive.cpp:27
KDL::JntArrayVel::q
JntArray q
Definition: jntarrayvel.hpp:48
KDL::SolverI::E_NOERROR
@ E_NOERROR
No error.
Definition: solveri.hpp:91
KDL::Chain
Definition: chain.hpp:35
KDL::Chain::getNrOfJoints
unsigned int getNrOfJoints() const
Request the total number of joints in the chain.
Definition: chain.hpp:71
KDL::SolverI::error
int error
Latest error, initialized to E_NOERROR in constructor.
Definition: solveri.hpp:149