chaindynparam.cpp
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 #include "chaindynparam.hpp"
23 #include "frames_io.hpp"
24 #include <iostream>
25 
26 namespace KDL {
27 
28  ChainDynParam::ChainDynParam(const Chain& _chain, Vector _grav):
29  chain(_chain),
30  nr(0),
31  nj(chain.getNrOfJoints()),
32  ns(chain.getNrOfSegments()),
33  grav(_grav),
34  jntarraynull(nj),
35  chainidsolver_coriolis( chain, Vector::Zero()),
36  chainidsolver_gravity( chain, grav),
37  wrenchnull(ns,Wrench::Zero()),
38  X(ns),
39  S(ns),
40  Ic(ns)
41  {
43  }
44 
51  wrenchnull.resize(ns,Wrench::Zero());
52  X.resize(ns);
53  S.resize(ns);
54  Ic.resize(ns);
55  }
56 
57 
58  //calculate inertia matrix H
59  int ChainDynParam::JntToMass(const JntArray &q, JntSpaceInertiaMatrix& H)
60  {
61  if(nj != chain.getNrOfJoints() || ns != chain.getNrOfSegments())
62  return (error = E_NOT_UP_TO_DATE);
63  //Check sizes when in debug mode
64  if(q.rows()!=nj || H.rows()!=nj || H.columns()!=nj )
65  return (error = E_SIZE_MISMATCH);
66  unsigned int k=0;
67  double q_;
68 
69  //Sweep from root to leaf
70  for(unsigned int i=0;i<ns;i++)
71  {
72  //Collect RigidBodyInertia
73  Ic[i]=chain.getSegment(i).getInertia();
75  {
76  q_=q(k);
77  k++;
78  }
79  else
80  {
81  q_=0.0;
82  }
83  X[i]=chain.getSegment(i).pose(q_);//Remark this is the inverse of the frame for transformations from the parent to the current coord frame
84  S[i]=X[i].M.Inverse(chain.getSegment(i).twist(q_,1.0));
85  }
86  //Sweep from leaf to root
87  int j,l;
88  k=nj-1; //reset k
89  for(int i=ns-1;i>=0;i--)
90  {
91 
92  if(i!=0)
93  {
94  //assumption that previous segment is parent
95  Ic[i-1]=Ic[i-1]+X[i]*Ic[i];
96  }
97 
98  F=Ic[i]*S[i];
100  {
101  H(k,k)=dot(S[i],F);
102  H(k,k)+=chain.getSegment(i).getJoint().getInertia(); // add joint inertia
103  j=k; //countervariable for the joints
104  l=i; //countervariable for the segments
105  while(l!=0) //go from leaf to root starting at i
106  {
107  //assumption that previous segment is parent
108  F=X[l]*F; //calculate the unit force (cfr S) for every segment: F[l-1]=X[l]*F[l]
109  l--; //go down a segment
110 
111  if(chain.getSegment(l).getJoint().getType()!=Joint::None) //if the joint connected to segment is not a fixed joint
112  {
113  j--;
114  H(k,j)=dot(F,S[l]); //here you actually match a certain not fixed joint with a segment
115  H(j,k)=H(k,j);
116  }
117  }
118  k--; //this if-loop should be repeated nj times (k=nj-1 to k=0)
119  }
120 
121  }
122  return (error = E_NOERROR);
123  }
124 
125  //calculate coriolis matrix C
126  int ChainDynParam::JntToCoriolis(const JntArray &q, const JntArray &q_dot, JntArray &coriolis)
127  {
128  //make a null matrix with the size of q_dotdot and a null wrench
130 
131 
132  //the calculation of coriolis matrix C
133  return chainidsolver_coriolis.CartToJnt(q, q_dot, jntarraynull, wrenchnull, coriolis);
134 
135  }
136 
137  //calculate gravity matrix G
139  {
140 
141  //make a null matrix with the size of q_dotdot and a null wrench
142 
144  //the calculation of coriolis matrix C
146  }
147 
149  {
150  }
151 
152 
153 }
std::vector< ArticulatedBodyInertia, Eigen::aligned_allocator< ArticulatedBodyInertia > > Ic
const Segment & getSegment(unsigned int nr) const
Definition: chain.cpp:68
unsigned int rows() const
Definition: jntarray.cpp:72
This class encapsulates a serial kinematic interconnection structure. It is built out of segments...
Definition: chain.hpp:35
Chain size changed.
Definition: solveri.hpp:97
unsigned int getNrOfSegments() const
Definition: chain.hpp:76
This class represents an fixed size array containing joint values of a KDL::Chain.
Definition: jntarray.hpp:69
std::vector< Wrench > wrenchnull
Input size does not match internal state.
Definition: solveri.hpp:99
doubleAcc dot(const VectorAcc &lhs, const VectorAcc &rhs)
Definition: frameacc.hpp:138
Frame pose(const double &q) const
Definition: segment.cpp:57
Twist twist(const double &q, const double &qdot) const
Definition: segment.cpp:62
represents both translational and rotational velocities.
Definition: frames.hpp:720
IMETHOD void SetToZero(Vector &v)
Definition: frames.hpp:1062
A concrete implementation of a 3 dimensional vector class.
Definition: frames.hpp:160
ChainDynParam(const Chain &chain, Vector _grav)
const Joint & getJoint() const
Definition: segment.hpp:118
int CartToJnt(const JntArray &q, const JntArray &q_dot, const JntArray &q_dotdot, const Wrenches &f_ext, JntArray &torques)
unsigned int getNrOfJoints() const
Definition: chain.hpp:71
virtual int JntToCoriolis(const JntArray &q, const JntArray &q_dot, JntArray &coriolis)
std::vector< Twist > S
void resize(unsigned int newSize)
Definition: jntarray.cpp:55
static Wrench Zero()
Definition: frames.hpp:186
ChainIdSolver_RNE chainidsolver_gravity
std::vector< Frame > X
virtual void updateInternalDataStructures()
const double & getInertia() const
Definition: joint.hpp:200
represents both translational and rotational acceleration.
Definition: frames.hpp:878
const Chain & chain
virtual int JntToMass(const JntArray &q, JntSpaceInertiaMatrix &H)
int error
Latest error, initialized to E_NOERROR in constructor.
Definition: solveri.hpp:149
ChainIdSolver_RNE chainidsolver_coriolis
static Vector Zero()
Definition: frames.hpp:139
const RigidBodyInertia & getInertia() const
Definition: segment.hpp:128
virtual int JntToGravity(const JntArray &q, JntArray &gravity)
const JointType & getType() const
Definition: joint.hpp:159


orocos_kdl
Author(s):
autogenerated on Sat Jun 15 2019 19:07:36