GCC Code Coverage Report


Directory: ./
File: include/pinocchio/algorithm/center-of-mass.hpp
Date: 2024-08-27 18:20:05
Exec Total Coverage
Lines: 0 2 0.0%
Branches: 0 0 -%

Line Branch Exec Source
1 //
2 // Copyright (c) 2015-2020 CNRS INRIA
3 //
4
5 #ifndef __pinocchio_algorithm_center_of_mass_hpp__
6 #define __pinocchio_algorithm_center_of_mass_hpp__
7
8 #include "pinocchio/multibody/model.hpp"
9 #include "pinocchio/multibody/data.hpp"
10
11 namespace pinocchio
12 {
13
14 ///
15 /// \brief Compute the total mass of the model and return it.
16 ///
17 /// \param[in] model The model structure of the rigid body system.
18 ///
19 /// \return Total mass of the model.
20 ///
21 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
22 inline Scalar computeTotalMass(const ModelTpl<Scalar, Options, JointCollectionTpl> & model);
23
24 ///
25 /// \brief Compute the total mass of the model, put it in data.mass[0] and return it.
26 ///
27 /// \param[in] model The model structure of the rigid body system.
28 /// \param[in] data The data structure of the rigid body system.
29 ///
30 /// \warning This method does not fill the whole data.mass vector. Only data.mass[0] is updated.
31 /// If you need the whole data.mass vector to be computed, use computeSubtreeMasses
32 ///
33 /// \return Total mass of the model.
34 ///
35 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
36 Scalar computeTotalMass(
37 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
38 DataTpl<Scalar, Options, JointCollectionTpl> & data);
39
40 ///
41 /// \brief Compute the mass of each kinematic subtree and store it in data.mass. The element
42 /// mass[0] corresponds to the total mass of the model.
43 ///
44 /// \param[in] model The model structure of the rigid body system.
45 /// \param[in] data The data structure of the rigid body system.
46 ///
47 /// \note If you are only interested in knowing the total mass of the model, computeTotalMass will
48 /// probably be slightly faster.
49 ///
50 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
51 void computeSubtreeMasses(
52 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
53 DataTpl<Scalar, Options, JointCollectionTpl> & data);
54
55 ///
56 /// \brief Computes the center of mass position of a given model according to a particular joint
57 /// configuration.
58 /// The result is accessible through data.com[0] for the full body com and data.com[i] for
59 /// the subtree supported by joint i (expressed in the joint i frame).
60 ///
61 /// \tparam JointCollection Collection of Joint types.
62 /// \tparam ConfigVectorType Type of the joint configuration vector.
63 ///
64 /// \param[in] model The model structure of the rigid body system.
65 /// \param[in] data The data structure of the rigid body system.
66 /// \param[in] q The joint configuration vector (dim model.nq).
67 /// \param[in] computeSubtreeComs If true, the algorithm computes also the center of mass of the
68 /// subtrees.
69 ///
70 /// \return The center of mass position of the full rigid body system expressed in the world
71 /// frame.
72 ///
73 template<
74 typename Scalar,
75 int Options,
76 template<typename, int>
77 class JointCollectionTpl,
78 typename ConfigVectorType>
79 const typename DataTpl<Scalar, Options, JointCollectionTpl>::Vector3 & centerOfMass(
80 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
81 DataTpl<Scalar, Options, JointCollectionTpl> & data,
82 const Eigen::MatrixBase<ConfigVectorType> & q,
83 const bool computeSubtreeComs = true);
84
85 ///
86 /// \brief Computes the center of mass position and velocity of a given model according to a
87 /// particular joint configuration and velocity.
88 /// The result is accessible through data.com[0], data.vcom[0] for the full body com
89 /// position and velocity. And data.com[i] and data.vcom[i] for the subtree supported by
90 /// joint i (expressed in the joint i frame).
91 ///
92 /// \tparam JointCollection Collection of Joint types.
93 /// \tparam ConfigVectorType Type of the joint configuration vector.
94 /// \tparam TangentVectorType Type of the joint velocity vector.
95 ///
96 /// \param[in] model The model structure of the rigid body system.
97 /// \param[in] data The data structure of the rigid body system.
98 /// \param[in] q The joint configuration vector (dim model.nq).
99 /// \param[in] v The joint velocity vector (dim model.nv).
100 /// \param[in] computeSubtreeComs If true, the algorithm computes also the center of mass of the
101 /// subtrees.
102 ///
103 /// \return The center of mass position of the full rigid body system expressed in the world
104 /// frame.
105 ///
106 template<
107 typename Scalar,
108 int Options,
109 template<typename, int>
110 class JointCollectionTpl,
111 typename ConfigVectorType,
112 typename TangentVectorType>
113 const typename DataTpl<Scalar, Options, JointCollectionTpl>::Vector3 & centerOfMass(
114 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
115 DataTpl<Scalar, Options, JointCollectionTpl> & data,
116 const Eigen::MatrixBase<ConfigVectorType> & q,
117 const Eigen::MatrixBase<TangentVectorType> & v,
118 const bool computeSubtreeComs = true);
119
120 ///
121 /// \brief Computes the center of mass position, velocity and acceleration of a given model
122 /// according to a particular joint configuration, velocity and acceleration.
123 /// The result is accessible through data.com[0], data.vcom[0], data.acom[0] for the full
124 /// body com position, velocity and acceleation. And data.com[i], data.vcom[i] and
125 /// data.acom[i] for the subtree supported by joint i (expressed in the joint i frame).
126 ///
127 /// \tparam JointCollection Collection of Joint types.
128 /// \tparam ConfigVectorType Type of the joint configuration vector.
129 /// \tparam TangentVectorType1 Type of the joint velocity vector.
130 /// \tparam TangentVectorType2 Type of the joint acceleration vector.
131 ///
132 /// \param[in] model The model structure of the rigid body system.
133 /// \param[in] data The data structure of the rigid body system.
134 /// \param[in] q The joint configuration vector (dim model.nq).
135 /// \param[in] v The joint velocity vector (dim model.nv).
136 /// \param[in] a The joint acceleration vector (dim model.nv).
137 /// \param[in] computeSubtreeComs If true, the algorithm computes also the center of mass of the
138 /// subtrees.
139 ///
140 /// \return The center of mass position of the full rigid body system expressed in the world
141 /// frame.
142 ///
143 template<
144 typename Scalar,
145 int Options,
146 template<typename, int>
147 class JointCollectionTpl,
148 typename ConfigVectorType,
149 typename TangentVectorType1,
150 typename TangentVectorType2>
151 const typename DataTpl<Scalar, Options, JointCollectionTpl>::Vector3 & centerOfMass(
152 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
153 DataTpl<Scalar, Options, JointCollectionTpl> & data,
154 const Eigen::MatrixBase<ConfigVectorType> & q,
155 const Eigen::MatrixBase<TangentVectorType1> & v,
156 const Eigen::MatrixBase<TangentVectorType2> & a,
157 const bool computeSubtreeComs = true);
158
159 ///
160 /// \brief Computes the center of mass position, velocity and acceleration of a given model
161 /// according to the current kinematic values contained in data and the requested kinematic_level.
162 /// The result is accessible through data.com[0], data.vcom[0] and data.acom[0] for the
163 /// full body com position and velocity. And data.com[i] and data.vcom[i] for the subtree
164 /// supported by joint i (expressed in the joint i frame).
165 ///
166 /// \tparam JointCollection Collection of Joint types.
167 ///
168 /// \param[in] model The model structure of the rigid body system.
169 /// \param[in] data The data structure of the rigid body system.
170 /// \param[in] kinematic_level if = POSITION, computes the CoM position, if = VELOCITY, also
171 /// computes the CoM velocity and if = ACCELERATION, it also computes the CoM acceleration.
172 /// \param[in] computeSubtreeComs If true, the algorithm computes also the center of mass of the
173 /// subtrees.
174 ///
175 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
176 const typename DataTpl<Scalar, Options, JointCollectionTpl>::Vector3 & centerOfMass(
177 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
178 DataTpl<Scalar, Options, JointCollectionTpl> & data,
179 KinematicLevel kinematic_level,
180 const bool computeSubtreeComs = true);
181
182 ///
183 /// \brief Computes the center of mass position, velocity and acceleration of a given model
184 /// according to the current kinematic values contained in data.
185 /// The result is accessible through data.com[0], data.vcom[0] and data.acom[0] for the
186 /// full body com position and velocity. And data.com[i] and data.vcom[i] for the subtree
187 /// supported by joint i (expressed in the joint i frame).
188 ///
189 /// \tparam JointCollection Collection of Joint types.
190 ///
191 /// \param[in] model The model structure of the rigid body system.
192 /// \param[in] data The data structure of the rigid body system.
193 /// \param[in] computeSubtreeComs If true, the algorithm computes also the center of mass of the
194 /// subtrees, expressed in the local coordinate frame of each joint.
195 ///
196 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
197 const typename DataTpl<Scalar, Options, JointCollectionTpl>::Vector3 & centerOfMass(
198 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
199 DataTpl<Scalar, Options, JointCollectionTpl> & data,
200 const bool computeSubtreeComs = true)
201 {
202 return centerOfMass(model, data, ACCELERATION, computeSubtreeComs);
203 }
204
205 ///
206 /// \brief Computes both the jacobian and the the center of mass position of a given model
207 /// according to a particular joint configuration.
208 /// The results are accessible through data.Jcom and data.com[0] and are both expressed in
209 /// the world frame. In addition, the algorithm also computes the Jacobian of all the
210 /// joints (\sa pinocchio::computeJointJacobians). And data.com[i] gives the center of mass
211 /// of the subtree supported by joint i (expressed in the world frame).
212 ///
213 /// \tparam JointCollection Collection of Joint types.
214 /// \tparam ConfigVectorType Type of the joint configuration vector.
215 ///
216 /// \param[in] model The model structure of the rigid body system.
217 /// \param[in] data The data structure of the rigid body system.
218 /// \param[in] q The joint configuration vector (dim model.nq).
219 /// \param[in] computeSubtreeComs If true, the algorithm also computes the centers of mass of the
220 /// subtrees, expressed in the world coordinate frame.
221 ///
222 /// \return The jacobian of center of mass position of the rigid body system expressed in the
223 /// world frame (matrix 3 x model.nv).
224 ///
225 template<
226 typename Scalar,
227 int Options,
228 template<typename, int>
229 class JointCollectionTpl,
230 typename ConfigVectorType>
231 const typename DataTpl<Scalar, Options, JointCollectionTpl>::Matrix3x & jacobianCenterOfMass(
232 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
233 DataTpl<Scalar, Options, JointCollectionTpl> & data,
234 const Eigen::MatrixBase<ConfigVectorType> & q,
235 const bool computeSubtreeComs = true);
236
237 ///
238 /// \brief Computes both the jacobian and the the center of mass position of a given model
239 /// according to the current value stored in data.
240 /// It assumes that forwardKinematics has been called first.
241 /// The results are accessible through data.Jcom and data.com[0] and are both expressed in
242 /// the world frame. In addition, the algorithm also computes the Jacobian of all the
243 /// joints (\sa pinocchio::computeJointJacobians). And data.com[i] gives the center of mass
244 /// of the subtree supported by joint i (expressed in the world frame).
245 ///
246 /// \tparam JointCollection Collection of Joint types.
247 /// \tparam ConfigVectorType Type of the joint configuration vector.
248 ///
249 /// \param[in] model The model structure of the rigid body system.
250 /// \param[in] data The data structure of the rigid body system.
251 /// \param[in] computeSubtreeComs If true, the algorithm also computes the center of mass of the
252 /// subtrees, expressed in the world coordinate frame.
253 ///
254 /// \return The jacobian of center of mass position of the rigid body system expressed in the
255 /// world frame (matrix 3 x model.nv).
256 ///
257 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
258 const typename DataTpl<Scalar, Options, JointCollectionTpl>::Matrix3x & jacobianCenterOfMass(
259 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
260 DataTpl<Scalar, Options, JointCollectionTpl> & data,
261 const bool computeSubtreeComs = true);
262
263 ///
264 /// \brief Computes the Jacobian of the center of mass of the given subtree according to a
265 /// particular joint configuration.
266 /// In addition, the algorithm also computes the Jacobian of all the joints (\sa
267 /// pinocchio::computeJointJacobians).
268 ///
269 /// \tparam JointCollection Collection of Joint types.
270 /// \tparam ConfigVectorType Type of the joint configuration vector.
271 /// \tparam Matrix3xLike Type of the output Jacobian matrix.
272 ///
273 /// \param[in] model The model structure of the rigid body system.
274 /// \param[in] data The data structure of the rigid body system.
275 /// \param[in] q The joint configuration vector (dim model.nq).
276 /// \param[in] rootSubtreeId Index of the parent joint supporting the subtree.
277 /// \param[out] res The Jacobian matrix where the results will be stored in (dim 3 x model.nv).
278 /// You must first fill J with zero elements, e.g. J.setZero().
279 ///
280 template<
281 typename Scalar,
282 int Options,
283 template<typename, int>
284 class JointCollectionTpl,
285 typename ConfigVectorType,
286 typename Matrix3xLike>
287 void jacobianSubtreeCenterOfMass(
288 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
289 DataTpl<Scalar, Options, JointCollectionTpl> & data,
290 const Eigen::MatrixBase<ConfigVectorType> & q,
291 const JointIndex & rootSubtreeId,
292 const Eigen::MatrixBase<Matrix3xLike> & res);
293
294 ///
295 /// \brief Computes the Jacobian of the center of mass of the given subtree according to the
296 /// current value stored in data.
297 /// It assumes that forwardKinematics has been called first.
298 ///
299 /// \tparam JointCollection Collection of Joint types.
300 /// \tparam Matrix3xLike Type of the output Jacobian matrix.
301 ///
302 /// \param[in] model The model structure of the rigid body system.
303 /// \param[in] data The data structure of the rigid body system.
304 /// \param[in] rootSubtreeId Index of the parent joint supporting the subtree.
305 /// \param[out] res The Jacobian matrix where the results will be stored in (dim 3 x model.nv).
306 /// You must first fill J with zero elements, e.g. J.setZero().
307 ///
308 template<
309 typename Scalar,
310 int Options,
311 template<typename, int>
312 class JointCollectionTpl,
313 typename Matrix3xLike>
314 void jacobianSubtreeCenterOfMass(
315 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
316 DataTpl<Scalar, Options, JointCollectionTpl> & data,
317 const JointIndex & rootSubtreeId,
318 const Eigen::MatrixBase<Matrix3xLike> & res);
319
320 ///
321 /// \brief Retrieves the Jacobian of the center of mass of the given subtree according to the
322 /// current value stored in data.
323 /// It assumes that pinocchio::jacobianCenterOfMass has been called first with
324 /// computeSubtreeComs equals to true.
325 ///
326 /// \tparam JointCollection Collection of Joint types.
327 /// \tparam Matrix3xLike Type of the output Jacobian matrix.
328 ///
329 /// \param[in] model The model structure of the rigid body system.
330 /// \param[in] data The data structure of the rigid body system.
331 /// \param[in] rootSubtreeId Index of the parent joint supporting the subtree.
332 /// \param[out] res The Jacobian matrix where the results will be stored in (dim 3 x model.nv).
333 /// You must first fill J with zero elements, e.g. J.setZero().
334 ///
335 template<
336 typename Scalar,
337 int Options,
338 template<typename, int>
339 class JointCollectionTpl,
340 typename Matrix3xLike>
341 void getJacobianSubtreeCenterOfMass(
342 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
343 const DataTpl<Scalar, Options, JointCollectionTpl> & data,
344 const JointIndex & rootSubtreeId,
345 const Eigen::MatrixBase<Matrix3xLike> & res);
346
347 /* If the CRBA has been run, then both COM and Jcom are easily available from
348 * the joint space mass matrix (data.M).
349 * Use the following function to infer them directly. In that case,
350 * the COM subtrees (also easily available from CRBA data) are not
351 * explicitely set. Use data.Ycrb[i].lever() to get them. */
352 ///
353 /// \brief Extracts the center of mass position from the joint space inertia matrix (also called
354 /// the mass matrix).
355 ///
356 /// \tparam JointCollection Collection of Joint types.
357 /// \tparam Matrix3xLike Type of the output Jacobian matrix.
358 ///
359 /// \param[in] model The model structure of the rigid body system.
360 /// \param[in] data The data structure of the rigid body system.
361 ///
362 /// \return The center of mass position of the rigid body system expressed in the world frame
363 /// (vector 3).
364 ///
365 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
366 const typename DataTpl<Scalar, Options, JointCollectionTpl>::Vector3 & getComFromCrba(
367 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
368 DataTpl<Scalar, Options, JointCollectionTpl> & data);
369
370 ///
371 /// \brief Extracts both the jacobian of the center of mass (CoM), the total mass of the system
372 /// and the CoM position from the joint space inertia matrix (also called the mass matrix).
373 /// The results are accessible through data.Jcom, data.mass[0] and data.com[0] and are both
374 /// expressed in the world frame.
375 ///
376 /// \tparam JointCollection Collection of Joint types.
377 ///
378 /// \param[in] model The model structure of the rigid body system.
379 /// \param[in] data The data structure of the rigid body system.
380 ///
381 /// \return The jacobian of the CoM expressed in the world frame (matrix 3 x model.nv).
382 ///
383 /// \remarks This extraction of inertial quantities is only valid for free-floating base systems.
384 ///
385 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
386 const typename DataTpl<Scalar, Options, JointCollectionTpl>::Matrix3x & getJacobianComFromCrba(
387 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
388 DataTpl<Scalar, Options, JointCollectionTpl> & data);
389
390 } // namespace pinocchio
391
392 /* --- Details -------------------------------------------------------------------- */
393 /* --- Details -------------------------------------------------------------------- */
394 /* --- Details -------------------------------------------------------------------- */
395 #include "pinocchio/algorithm/center-of-mass.hxx"
396
397 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
398 #include "pinocchio/algorithm/center-of-mass.txx"
399 #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
400
401 #endif // ifndef __pinocchio_algorithm_center_of_mass_hpp__
402