KDL  1.4.0
chaindynparam.hpp
Go to the documentation of this file.
1 // Copyright (C) 2009 Dominick Vanthienen <dominick dot vanthienen at mech dot kuleuven dot be>
2 
3 // Version: 1.0
4 // Author: Dominick Vanthienen <dominick dot vanthienen 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 KDLCHAINDYNPARAM_HPP
23 #define KDLCHAINDYNPARAM_HPP
24 
28 #include <Eigen/StdVector>
29 
30 namespace KDL {
31 
48  {
49  public:
50  ChainDynParam(const Chain& chain, Vector _grav);
51  virtual ~ChainDynParam();
52 
53  virtual int JntToCoriolis(const JntArray &q, const JntArray &q_dot, JntArray &coriolis);
54  virtual int JntToMass(const JntArray &q, JntSpaceInertiaMatrix& H);
55  virtual int JntToGravity(const JntArray &q,JntArray &gravity);
56 
58  virtual void updateInternalDataStructures();
59 
60  private:
61  const Chain& chain;
62  int nr;
63  unsigned int nj;
64  unsigned int ns;
70  std::vector<Wrench> wrenchnull;
71  std::vector<Frame> X;
72  std::vector<Twist> S;
73  //std::vector<RigidBodyInertia> I;
74  std::vector<ArticulatedBodyInertia, Eigen::aligned_allocator<ArticulatedBodyInertia> > Ic;
77 
78  };
79 
80 }
81 
82 #endif
jntspaceinertiamatrix.hpp
KDL::ChainDynParam::wrenchnull
std::vector< Wrench > wrenchnull
Definition: chaindynparam.hpp:70
KDL::ChainIdSolver_RNE
Recursive newton euler inverse dynamics solver.
Definition: chainidsolver_recursive_newton_euler.hpp:40
KDL::JntArray
Definition: jntarray.hpp:69
KDL::ChainIdSolver_RNE::CartToJnt
int CartToJnt(const JntArray &q, const JntArray &q_dot, const JntArray &q_dotdot, const Wrenches &f_ext, JntArray &torques)
Function to calculate from Cartesian forces to joint torques.
Definition: chainidsolver_recursive_newton_euler.cpp:44
KDL::ChainDynParam::updateInternalDataStructures
virtual void updateInternalDataStructures()
Update the internal data structures.
Definition: chaindynparam.cpp:45
KDL::Vector::Zero
static Vector Zero()
Definition: frames.inl:138
KDL::Segment::getJoint
const Joint & getJoint() const
Request the joint of the segment.
Definition: segment.hpp:118
KDL::ChainDynParam::ag
Twist ag
Definition: chaindynparam.hpp:76
frames_io.hpp
KDL::JntArray::resize
void resize(unsigned int newSize)
Resize the array.
Definition: jntarray.cpp:55
chainidsolver_recursive_newton_euler.hpp
KDL::ChainDynParam::Ic
std::vector< ArticulatedBodyInertia, Eigen::aligned_allocator< ArticulatedBodyInertia > > Ic
Definition: chaindynparam.hpp:74
KDL::SolverI::E_NOT_UP_TO_DATE
@ E_NOT_UP_TO_DATE
Chain size changed.
Definition: solveri.hpp:97
KDL::ChainDynParam
Implementation of a method to calculate the matrices H (inertia),C(coriolis) and G(gravitation) for t...
Definition: chaindynparam.hpp:47
KDL::ChainDynParam::X
std::vector< Frame > X
Definition: chaindynparam.hpp:71
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
chaindynparam.hpp
KDL::Vector
A concrete implementation of a 3 dimensional vector class.
Definition: frames.hpp:160
KDL::Twist
represents both translational and rotational velocities.
Definition: frames.hpp:720
KDL::JntArray::rows
unsigned int rows() const
Returns the number of rows (size) of the array.
Definition: jntarray.cpp:72
KDL::ChainDynParam::nj
unsigned int nj
Definition: chaindynparam.hpp:63
dot
doubleAcc dot(const VectorAcc &lhs, const VectorAcc &rhs)
Definition: frameacc.inl:137
KDL::Chain::getSegment
const Segment & getSegment(unsigned int nr) const
Request the nr'd segment of the chain.
Definition: chain.cpp:68
KDL::ChainDynParam::ns
unsigned int ns
Definition: chaindynparam.hpp:64
KDL::SolverI::E_SIZE_MISMATCH
@ E_SIZE_MISMATCH
Input size does not match internal state.
Definition: solveri.hpp:99
KDL::Wrench
represents both translational and rotational acceleration.
Definition: frames.hpp:878
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::ChainDynParam::JntToMass
virtual int JntToMass(const JntArray &q, JntSpaceInertiaMatrix &H)
Definition: chaindynparam.cpp:59
KDL::ChainDynParam::nr
int nr
Definition: chaindynparam.hpp:62
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::ChainDynParam::ChainDynParam
ChainDynParam(const Chain &chain, Vector _grav)
Definition: chaindynparam.cpp:28
KDL::Joint::None
@ None
Definition: joint.hpp:47
KDL::SolverI
Solver interface supporting storage and description of the latest error.
Definition: solveri.hpp:84
KDL::Wrench::Zero
static Wrench Zero()
Definition: frames.inl:185
KDL::ChainDynParam::grav
Vector grav
Definition: chaindynparam.hpp:65
KDL::ChainDynParam::S
std::vector< Twist > S
Definition: chaindynparam.hpp:72
KDL::ChainDynParam::chainidsolver_coriolis
ChainIdSolver_RNE chainidsolver_coriolis
Definition: chaindynparam.hpp:68
KDL::ChainDynParam::chainidsolver_gravity
ChainIdSolver_RNE chainidsolver_gravity
Definition: chaindynparam.hpp:69
articulatedbodyinertia.hpp
KDL::ChainDynParam::JntToGravity
virtual int JntToGravity(const JntArray &q, JntArray &gravity)
Definition: chaindynparam.cpp:137
KDL::ChainDynParam::F
Wrench F
Definition: chaindynparam.hpp:75
KDL::ChainDynParam::~ChainDynParam
virtual ~ChainDynParam()
Definition: chaindynparam.cpp:147
KDL::ChainDynParam::vectornull
Vector vectornull
Definition: chaindynparam.hpp:66
KDL::Joint::getType
const JointType & getType() const
Request the type of the joint.
Definition: joint.hpp:159
KDL::SetToZero
void SetToZero(Jacobian &jac)
Definition: jacobian.cpp:80
KDL::SolverI::E_NOERROR
@ E_NOERROR
No error.
Definition: solveri.hpp:91
KDL::ChainDynParam::chain
const Chain & chain
Definition: chaindynparam.hpp:61
KDL::ChainDynParam::JntToCoriolis
virtual int JntToCoriolis(const JntArray &q, const JntArray &q_dot, JntArray &coriolis)
Definition: chaindynparam.cpp:125
KDL::Chain
Definition: chain.hpp:35
KDL::Segment::getInertia
const RigidBodyInertia & getInertia() const
Request the inertia of the segment.
Definition: segment.hpp:128
KDL::Chain::getNrOfJoints
unsigned int getNrOfJoints() const
Request the total number of joints in the chain.
Definition: chain.hpp:71
KDL::ChainDynParam::jntarraynull
JntArray jntarraynull
Definition: chaindynparam.hpp:67
KDL::SolverI::error
int error
Latest error, initialized to E_NOERROR in constructor.
Definition: solveri.hpp:149
KDL::ChainIdSolver_RNE::updateInternalDataStructures
virtual void updateInternalDataStructures()
Update the internal data structures.
Definition: chainidsolver_recursive_newton_euler.cpp:34