pinocchio  UNKNOWN
compute-all-terms.hpp
1 //
2 // Copyright (c) 2015-2017 CNRS
3 //
4 // This file is part of Pinocchio
5 // Pinocchio is free software: you can redistribute it
6 // and/or modify it under the terms of the GNU Lesser General Public
7 // License as published by the Free Software Foundation, either version
8 // 3 of the License, or (at your option) any later version.
9 //
10 // Pinocchio is distributed in the hope that it will be
11 // useful, but WITHOUT ANY WARRANTY; without even the implied warranty
12 // of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
13 // General Lesser Public License for more details. You should have
14 // received a copy of the GNU Lesser General Public License along with
15 // Pinocchio If not, see
16 // <http://www.gnu.org/licenses/>.
17 
18 #ifndef __se3_compute_all_terms_hpp__
19 #define __se3_compute_all_terms_hpp__
20 
21 #include "pinocchio/multibody/visitor.hpp"
22 #include "pinocchio/multibody/model.hpp"
23 #include "pinocchio/multibody/data.hpp"
24 #include "pinocchio/spatial/act-on-set.hpp"
25 #include "pinocchio/algorithm/center-of-mass.hpp"
26 #include "pinocchio/algorithm/energy.hpp"
27 #include "pinocchio/algorithm/check.hpp"
28 
29 namespace se3
30 {
48  inline void
49  computeAllTerms(const Model & model,
50  Data & data,
51  const Eigen::VectorXd & q,
52  const Eigen::VectorXd & v);
53 
54 } // namespace se3
55 
56 
57 /* --- Details -------------------------------------------------------------------- */
58 namespace se3
59 {
60 
61  struct CATForwardStep : public fusion::JointVisitor<CATForwardStep>
62  {
63  typedef boost::fusion::vector< const se3::Model &,
64  se3::Data &,
65  const Eigen::VectorXd &,
66  const Eigen::VectorXd &
67  > ArgsType;
68 
69  JOINT_VISITOR_INIT(CATForwardStep);
70 
71  template<typename JointModel>
72  static void algo(const se3::JointModelBase<JointModel> & jmodel,
74  const se3::Model & model,
75  se3::Data & data,
76  const Eigen::VectorXd & q,
77  const Eigen::VectorXd & v)
78  {
79  using namespace Eigen;
80  using namespace se3;
81 
82  const Model::JointIndex & i = (Model::JointIndex) jmodel.id();
83  const Model::JointIndex & parent = model.parents[i];
84 
85  jmodel.calc(jdata.derived(),q,v);
86 
87  // CRBA
88  data.liMi[i] = model.jointPlacements[i]*jdata.M();
89  data.Ycrb[i] = model.inertias[i];
90 
91  // Jacobian + NLE
92  data.v[i] = jdata.v();
93 
94  if(parent>0)
95  {
96  data.oMi[i] = data.oMi[parent]*data.liMi[i];
97  data.v[i] += data.liMi[i].actInv(data.v[parent]);
98  }
99  else
100  data.oMi[i] = data.liMi[i];
101 
102  jmodel.jointCols(data.J) = data.oMi[i].act(jdata.S());
103 
104  data.a_gf[i] = data.a[i] = jdata.c() + (data.v[i] ^ jdata.v());
105  if (parent > 0)
106  data.a[i] += data.liMi[i].actInv(data.a[parent]);
107 
108  data.a_gf[i] += data.liMi[i].actInv(data.a_gf[parent]);
109 
110  data.f[i] = model.inertias[i]*data.a_gf[i] + model.inertias[i].vxiv(data.v[i]); // -f_ext
111 
112  // CoM
113  const double mass = model.inertias[i].mass();
114  const SE3::Vector3 & lever = model.inertias[i].lever();
115 
116  data.com[i] = mass * lever;
117  data.mass[i] = mass;
118 
119  data.vcom[i] = mass * (data.v[i].angular().cross(lever) + data.v[i].linear());
120  }
121 
122  };
123 
124  struct CATBackwardStep : public fusion::JointVisitor<CATBackwardStep>
125  {
126  typedef boost::fusion::vector<const Model &,
127  Data &> ArgsType;
128 
129  JOINT_VISITOR_INIT(CATBackwardStep);
130 
131  template<typename JointModel>
132  static void algo(const JointModelBase<JointModel> & jmodel,
134  const Model & model,
135  Data & data)
136  {
137  /*
138  * F[1:6,i] = Y*S
139  * M[i,SUBTREE] = S'*F[1:6,SUBTREE]
140  * if li>0
141  * Yli += liXi Yi
142  * F[1:6,SUBTREE] = liXi F[1:6,SUBTREE]
143  */
144  const Model::JointIndex & i = (Model::JointIndex) jmodel.id();
145  const Model::JointIndex & parent = model.parents[i];
146  const SE3 & oMi = data.oMi[i];
147 
148  /* F[1:6,i] = Y*S */
149  jmodel.jointCols(data.Fcrb[i]) = data.Ycrb[i] * jdata.S();
150 
151  /* M[i,SUBTREE] = S'*F[1:6,SUBTREE] */
152  data.M.block(jmodel.idx_v(),jmodel.idx_v(),jmodel.nv(),data.nvSubtree[i])
153  = jdata.S().transpose()*data.Fcrb[i].middleCols(jmodel.idx_v(),data.nvSubtree[i]);
154 
155 
156  jmodel.jointVelocitySelector(data.nle) = jdata.S().transpose()*data.f[i];
157  if(parent>0)
158  {
159  /* Yli += liXi Yi */
160  data.Ycrb[parent] += data.liMi[i].act(data.Ycrb[i]);
161 
162  /* F[1:6,SUBTREE] = liXi F[1:6,SUBTREE] */
163  Eigen::Block<typename Data::Matrix6x> jF
164  = data.Fcrb[parent].block(0,jmodel.idx_v(),6,data.nvSubtree[i]);
165  Eigen::Block<typename Data::Matrix6x> iF
166  = data.Fcrb[i].block(0,jmodel.idx_v(),6,data.nvSubtree[i]);
167  forceSet::se3Action(data.liMi[i], iF, jF);
168 
169  data.f[parent] += data.liMi[i].act(data.f[i]);
170  }
171 
172  // CoM
173  const SE3 & liMi = data.liMi[i];
174 
175  data.com[parent] += (liMi.rotation()*data.com[i]
176  + data.mass[i] * liMi.translation());
177 
178  SE3::Vector3 com_in_world (oMi.rotation() * data.com[i] + data.mass[i] * oMi.translation());
179 
180  data.vcom[parent] += liMi.rotation()*data.vcom[i];
181  data.mass[parent] += data.mass[i];
182 
183  typedef Data::Matrix6x Matrix6x;
184  typedef typename SizeDepType<JointModel::NV>::template ColsReturn<Matrix6x>::Type ColBlock;
185 
186  ColBlock Jcols = jmodel.jointCols(data.J);
187 
188  if( JointModel::NV==1 )
189  data.Jcom.col(jmodel.idx_v())
190  = data.mass[i] * Jcols.template topLeftCorner<3,1>()
191  - com_in_world.cross(Jcols.template bottomLeftCorner<3,1>()) ;
192  else
193  jmodel.jointCols(data.Jcom)
194  = data.mass[i] * Jcols.template topRows<3>()
195  - skew(com_in_world) * Jcols.template bottomRows<3>();
196 
197  data.com[i] /= data.mass[i];
198  data.vcom[i] /= data.mass[i];
199  }
200  };
201 
202  inline void
203  computeAllTerms(const Model & model,
204  Data & data,
205  const Eigen::VectorXd & q,
206  const Eigen::VectorXd & v)
207  {
208  assert(model.check(data) && "data is not consistent with model.");
209  data.v[0].setZero();
210  data.a[0].setZero();
211  data.a_gf[0] = -model.gravity;
212 
213  data.mass[0] = 0;
214  data.com[0].setZero ();
215  data.vcom[0].setZero ();
216 
217  for(Model::JointIndex i=1;i<(Model::JointIndex) model.njoints;++i)
218  {
219  CATForwardStep::run(model.joints[i],data.joints[i],
220  CATForwardStep::ArgsType(model,data,q,v));
221  }
222 
223  for(Model::JointIndex i=(Model::JointIndex)(model.njoints-1);i>0;--i)
224  {
225  CATBackwardStep::run(model.joints[i],data.joints[i],
226  CATBackwardStep::ArgsType(model,data));
227  }
228 
229  // CoM
230  data.com[0] /= data.mass[0];
231  data.vcom[0] /= data.mass[0];
232 
233  // JCoM
234  data.Jcom /= data.mass[0];
235 
236  // Energy
237  kineticEnergy(model, data, q, v, false);
238  potentialEnergy(model, data, q, false);
239 
240  }
241 } // namespace se3
242 
243 
244 #endif // ifndef __se3_compute_all_terms_hpp__
245 
container::aligned_vector< Motion > a
Vector of joint accelerations expressed at the centers of the joints.
Definition: data.hpp:58
Matrix3x Jcom
Jacobien of center of mass.
Definition: data.hpp:260
container::aligned_vector< Eigen::Vector3d > vcom
Vector of subtree center of mass linear velocities expressed in the root joint of the subtree...
Definition: data.hpp:250
container::aligned_vector< SE3 > jointPlacements
Placement (SE3) of the input of joint i regarding to the parent joint output li.
Definition: model.hpp:67
std::vector< int > nvSubtree
Dimension of the subtree motion space (for CRBA)
Definition: data.hpp:195
void computeAllTerms(const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v)
Computes efficiently all the terms needed for dynamic simulation. It is equivalent to the call at the...
double potentialEnergy(const Model &model, Data &data, const Eigen::VectorXd &q, const bool update_kinematics=true)
Computes the potential energy of the system, i.e. the potential energy linked to the gravity field...
Definition: energy.hpp:91
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef Eigen::Matrix< double, 6, Eigen::Dynamic > Matrix6x
The 6d jacobian type (temporary)
Definition: data.hpp:45
JointModelVector joints
Model of joint i, encapsulated in a JointModelAccessor.
Definition: model.hpp:70
container::aligned_vector< Inertia > Ycrb
Vector of sub-tree composite rigid body inertias, i.e. the apparent inertia of the subtree supported ...
Definition: data.hpp:110
double kineticEnergy(const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const bool update_kinematics=true)
Computes the kinetic energy of the system. The result is accessible through data.kinetic_energy.
Definition: energy.hpp:70
void skew(const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3 > &M)
Computes the skew representation of a given 3d vector, i.e. the antisymmetric matrix representation o...
Definition: skew.hpp:34
Matrix6x J
Jacobian of joint placements.
Definition: data.hpp:217
std::vector< JointIndex > parents
Joint parent of joint i, denoted li (li==parents[i]).
Definition: model.hpp:73
container::aligned_vector< Matrix6x > Fcrb
Spatial forces set, used in CRBA and CCRBA.
Definition: data.hpp:190
Eigen::VectorXd nle
Vector of Non Linear Effects (dim model.nv). It corresponds to concatenation of the Coriolis...
Definition: data.hpp:98
container::aligned_vector< Motion > a_gf
Vector of joint accelerations due to the gravity field.
Definition: data.hpp:64
container::aligned_vector< Eigen::Vector3d > com
Vector of subtree center of mass positions expressed in the root joint of the subtree. In other words, com[j] is the CoM position of the subtree supported by joint and expressed in the joint frame . The element com[0] corresponds to the center of mass position of the whole model and expressed in the global frame.
Definition: data.hpp:247
JointDataVector joints
Vector of se3::JointData associated to the se3::JointModel stored in model, encapsulated in JointData...
Definition: data.hpp:55
Motion gravity
Spatial gravity of the model.
Definition: model.hpp:106
Eigen::MatrixXd M
The joint space inertia matrix (a square matrix of dim model.nv).
Definition: data.hpp:116
container::aligned_vector< SE3 > liMi
Vector of relative joint placements (wrt the body parent).
Definition: data.hpp:90
container::aligned_vector< SE3 > oMi
Vector of absolute joint placements (wrt the world).
Definition: data.hpp:87
bool check(const AlgorithmCheckerBase< D > &checker=AlgorithmCheckerBase< D >()) const
Definition: model.hpp:331
container::aligned_vector< Inertia > inertias
Spatial inertias of the body i expressed in the supporting joint frame i.
Definition: model.hpp:64
container::aligned_vector< Force > f
Vector of body forces expressed in the local frame of the joint. For each body, the force represents ...
Definition: data.hpp:74
container::aligned_vector< Motion > v
Vector of joint velocities expressed at the centers of the joints.
Definition: data.hpp:67
int njoints
Number of joints.
Definition: model.hpp:55
std::vector< double > mass
Vector of subtree mass. In other words, mass[j] is the mass of the subtree supported by joint ...
Definition: data.hpp:256