GCC Code Coverage Report


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

Line Branch Exec Source
1 //
2 // Copyright (c) 2018-2020 CNRS INRIA
3 //
4
5 #ifndef __pinocchio_algorithm_regressor_hpp__
6 #define __pinocchio_algorithm_regressor_hpp__
7
8 #include "pinocchio/multibody/model.hpp"
9 #include "pinocchio/multibody/data.hpp"
10
11 namespace pinocchio
12 {
13
14 ///
15 /// \copydoc computeJointKinematicRegressor(const ModelTpl<Scalar,Options,JointCollectionTpl>
16 /// &,const DataTpl<Scalar,Options,JointCollectionTpl> &, const JointIndex, const ReferenceFrame,
17 /// const SE3Tpl<Scalar,Options> &)
18 ///
19 /// \param[out] kinematic_regressor The kinematic regressor containing the result. Matrix of size
20 /// 6*(model.njoints-1) initialized to 0.
21 ///
22 template<
23 typename Scalar,
24 int Options,
25 template<typename, int>
26 class JointCollectionTpl,
27 typename Matrix6xReturnType>
28 void computeJointKinematicRegressor(
29 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
30 const DataTpl<Scalar, Options, JointCollectionTpl> & data,
31 const JointIndex joint_id,
32 const ReferenceFrame rf,
33 const SE3Tpl<Scalar, Options> & placement,
34 const Eigen::MatrixBase<Matrix6xReturnType> & kinematic_regressor);
35
36 ///
37 /// \brief Computes the kinematic regressor that links the joint placements variations of the
38 /// whole kinematic tree
39 /// to the placement variation of the frame rigidly attached to the joint and given by its
40 /// placement w.r.t. to the joint frame.
41 ///
42 /// \remarks It assumes that the \ref forwardKinematics(const
43 /// ModelTpl<Scalar,Options,JointCollectionTpl> &, DataTpl<Scalar,Options,JointCollectionTpl> &,
44 /// const Eigen::MatrixBase<ConfigVectorType> &) has been called first.
45 ///
46 /// \param[in] model The model structure of the rigid body system.
47 /// \param[in] data The data structure of the rigid body system.
48 /// \param[in] joint_id Index of the joint.
49 /// \param[in] rf Reference frame in which the result is expressed (LOCAL, LOCAL_WORLD_ALIGNED or
50 /// WORLD). \param[in] placement Relative placement to the joint frame.
51 ///
52 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
53 typename DataTpl<Scalar, Options, JointCollectionTpl>::Matrix6x computeJointKinematicRegressor(
54 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
55 const DataTpl<Scalar, Options, JointCollectionTpl> & data,
56 const JointIndex joint_id,
57 const ReferenceFrame rf,
58 const SE3Tpl<Scalar, Options> & placement)
59 {
60 typedef typename DataTpl<Scalar, Options, JointCollectionTpl>::Matrix6x ReturnType;
61 ReturnType res(ReturnType::Zero(6, (model.njoints - 1) * 6));
62
63 computeJointKinematicRegressor(model, data, joint_id, rf, placement, res);
64
65 return res;
66 }
67
68 ///
69 /// \copydoc computeJointKinematicRegressor(const ModelTpl<Scalar,Options,JointCollectionTpl>
70 /// &,const DataTpl<Scalar,Options,JointCollectionTpl> &, const JointIndex, const ReferenceFrame)
71 ///
72 /// \param[out] kinematic_regressor The kinematic regressor containing the result. Matrix of size
73 /// 6*(model.njoints-1) initialized to 0.
74 ///
75 template<
76 typename Scalar,
77 int Options,
78 template<typename, int>
79 class JointCollectionTpl,
80 typename Matrix6xReturnType>
81 void computeJointKinematicRegressor(
82 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
83 const DataTpl<Scalar, Options, JointCollectionTpl> & data,
84 const JointIndex joint_id,
85 const ReferenceFrame rf,
86 const Eigen::MatrixBase<Matrix6xReturnType> & kinematic_regressor);
87
88 ///
89 /// \brief Computes the kinematic regressor that links the joint placement variations of the whole
90 /// kinematic tree
91 /// to the placement variation of the joint given as input.
92 ///
93 /// \remarks It assumes that the \ref forwardKinematics(const
94 /// ModelTpl<Scalar,Options,JointCollectionTpl> &, DataTpl<Scalar,Options,JointCollectionTpl> &,
95 /// const Eigen::MatrixBase<ConfigVectorType> &) has been called first.
96 ///
97 /// \param[in] model The model structure of the rigid body system.
98 /// \param[in] data The data structure of the rigid body system.
99 /// \param[in] joint_id Index of the joint.
100 /// \param[in] rf Reference frame in which the result is expressed (LOCAL, LOCAL_WORLD_ALIGNED or
101 /// WORLD).
102 ///
103 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
104 typename DataTpl<Scalar, Options, JointCollectionTpl>::Matrix6x computeJointKinematicRegressor(
105 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
106 const DataTpl<Scalar, Options, JointCollectionTpl> & data,
107 const JointIndex joint_id,
108 const ReferenceFrame rf)
109 {
110 typedef typename DataTpl<Scalar, Options, JointCollectionTpl>::Matrix6x ReturnType;
111 ReturnType res(ReturnType::Zero(6, (model.njoints - 1) * 6));
112
113 computeJointKinematicRegressor(model, data, joint_id, rf, res);
114
115 return res;
116 }
117
118 ///
119 /// \copydoc computeFrameKinematicRegressor(const ModelTpl<Scalar,Options,JointCollectionTpl> &,
120 /// DataTpl<Scalar,Options,JointCollectionTpl> &, const FrameIndex, const ReferenceFrame)
121 ///
122 /// \param[out] kinematic_regressor The kinematic regressor containing the result. Matrix of size
123 /// 6*(model.njoints-1) initialized to 0.
124 ///
125 template<
126 typename Scalar,
127 int Options,
128 template<typename, int>
129 class JointCollectionTpl,
130 typename Matrix6xReturnType>
131 void computeFrameKinematicRegressor(
132 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
133 DataTpl<Scalar, Options, JointCollectionTpl> & data,
134 const FrameIndex frame_id,
135 const ReferenceFrame rf,
136 const Eigen::MatrixBase<Matrix6xReturnType> & kinematic_regressor);
137
138 ///
139 /// \brief Computes the kinematic regressor that links the joint placement variations of the whole
140 /// kinematic tree
141 /// to the placement variation of the frame given as input.
142 ///
143 /// \remarks It assumes that the \ref framesForwardKinematics(const
144 /// ModelTpl<Scalar,Options,JointCollectionTpl> &, DataTpl<Scalar,Options,JointCollectionTpl> &,
145 /// const Eigen::MatrixBase<ConfigVectorType> &) has been called first.
146 ///
147 /// \param[in] model The model structure of the rigid body system.
148 /// \param[in] data The data structure of the rigid body system.
149 /// \param[in] frame_id Index of the frame.
150 /// \param[in] rf Reference frame in which the result is expressed (LOCAL, LOCAL_WORLD_ALIGNED or
151 /// WORLD).
152 ///
153 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
154 typename DataTpl<Scalar, Options, JointCollectionTpl>::Matrix6x computeFrameKinematicRegressor(
155 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
156 DataTpl<Scalar, Options, JointCollectionTpl> & data,
157 const FrameIndex frame_id,
158 const ReferenceFrame rf)
159 {
160 typedef typename DataTpl<Scalar, Options, JointCollectionTpl>::Matrix6x ReturnType;
161 ReturnType res(ReturnType::Zero(6, (model.njoints - 1) * 6));
162
163 computeFrameKinematicRegressor(model, data, frame_id, rf, res);
164
165 return res;
166 }
167
168 ///
169 /// \brief Computes the static regressor that links the center of mass positions of all the links
170 /// to the center of mass of the complete model according to the current configuration of
171 /// the robot.
172 ///
173 /// The result is stored in `data.staticRegressor` and it corresponds to a matrix \f$ Y \f$ such
174 /// that \f$ c = Y(q,\dot{q},\ddot{q})\tilde{\pi} \f$ where \f$ \tilde{\pi} =
175 /// (\tilde{\pi}_1^T\ \dots\ \tilde{\pi}_n^T)^T \f$ and \f$ \tilde{\pi}_i =
176 /// \text{model.inertias[i].toDynamicParameters().head<4>()} \f$
177 ///
178 /// \tparam JointCollection Collection of Joint types.
179 /// \tparam ConfigVectorType Type of the joint configuration vector.
180 ///
181 /// \param[in] model The model structure of the rigid body system.
182 /// \param[in] data The data structure of the rigid body system.
183 /// \param[in] q The joint configuration vector (dim model.nq).
184 ///
185 /// \return The static regressor of the system.
186 ///
187 template<
188 typename Scalar,
189 int Options,
190 template<typename, int>
191 class JointCollectionTpl,
192 typename ConfigVectorType>
193 inline typename DataTpl<Scalar, Options, JointCollectionTpl>::Matrix3x & computeStaticRegressor(
194 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
195 DataTpl<Scalar, Options, JointCollectionTpl> & data,
196 const Eigen::MatrixBase<ConfigVectorType> & q);
197
198 ///
199 /// \brief Computes the regressor for the dynamic parameters of a single rigid body.
200 ///
201 /// The result is such that
202 /// \f$ I a + v \times I v = bodyRegressor(v,a) * I.toDynamicParameters() \f$
203 ///
204 /// \param[in] v Velocity of the rigid body
205 /// \param[in] a Acceleration of the rigid body
206 /// \param[out] regressor The resulting regressor of the body.
207 ///
208 template<typename MotionVelocity, typename MotionAcceleration, typename OutputType>
209 inline void bodyRegressor(
210 const MotionDense<MotionVelocity> & v,
211 const MotionDense<MotionAcceleration> & a,
212 const Eigen::MatrixBase<OutputType> & regressor);
213
214 ///
215 /// \brief Computes the regressor for the dynamic parameters of a single rigid body.
216 ///
217 /// The result is such that
218 /// \f$ I a + v \times I v = bodyRegressor(v,a) * I.toDynamicParameters() \f$
219 ///
220 /// \param[in] v Velocity of the rigid body
221 /// \param[in] a Acceleration of the rigid body
222 ///
223 /// \return The regressor of the body.
224 ///
225 template<typename MotionVelocity, typename MotionAcceleration>
226 inline Eigen::Matrix<
227 typename MotionVelocity::Scalar,
228 6,
229 10,
230 PINOCCHIO_EIGEN_PLAIN_TYPE(typename MotionVelocity::Vector3)::Options>
231 bodyRegressor(const MotionDense<MotionVelocity> & v, const MotionDense<MotionAcceleration> & a);
232
233 ///
234 /// \brief Computes the regressor for the dynamic parameters of a rigid body attached to a given
235 /// joint,
236 /// puts the result in data.bodyRegressor and returns it.
237 ///
238 /// This algorithm assumes RNEA has been run to compute the acceleration and gravitational
239 /// effects.
240 ///
241 /// The result is such that
242 /// \f$ f = \text{jointBodyRegressor(model,data,joint_id) * I.toDynamicParameters()} \f$
243 /// where \f$ f \f$ is the net force acting on the body, including gravity
244 ///
245 /// \param[in] model The model structure of the rigid body system.
246 /// \param[in] data The data structure of the rigid body system.
247 /// \param[in] joint_id The id of the joint.
248 ///
249 /// \return The regressor of the body.
250 ///
251 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
252 inline typename DataTpl<Scalar, Options, JointCollectionTpl>::BodyRegressorType &
253 jointBodyRegressor(
254 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
255 DataTpl<Scalar, Options, JointCollectionTpl> & data,
256 JointIndex joint_id);
257
258 ///
259 /// \brief Computes the regressor for the dynamic parameters of a rigid body attached to a given
260 /// frame,
261 /// puts the result in data.bodyRegressor and returns it.
262 ///
263 /// This algorithm assumes RNEA has been run to compute the acceleration and gravitational
264 /// effects.
265 ///
266 /// The result is such that
267 /// \f$ f = \text{frameBodyRegressor(model,data,frame_id) * I.toDynamicParameters()} \f$
268 /// where \f$ f \f$ is the net force acting on the body, including gravity
269 ///
270 /// \param[in] model The model structure of the rigid body system.
271 /// \param[in] data The data structure of the rigid body system.
272 /// \param[in] frame_id The id of the frame.
273 ///
274 /// \return The dynamic regressor of the body.
275 ///
276 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
277 inline typename DataTpl<Scalar, Options, JointCollectionTpl>::BodyRegressorType &
278 frameBodyRegressor(
279 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
280 DataTpl<Scalar, Options, JointCollectionTpl> & data,
281 FrameIndex frame_id);
282
283 ///
284 /// \brief Computes the joint torque regressor that links the joint torque
285 /// to the dynamic parameters of each link according to the current the robot motion.
286 ///
287 /// The result is stored in `data.jointTorqueRegressor` and it corresponds to a matrix \f$ Y \f$
288 /// such that \f$ \tau = Y(q,\dot{q},\ddot{q})\pi \f$ where \f$ \pi = (\pi_1^T\ \dots\ \pi_n^T)^T
289 /// \f$ and \f$ \pi_i = \text{model.inertias[i].toDynamicParameters()} \f$
290 ///
291 /// \tparam JointCollection Collection of Joint types.
292 /// \tparam ConfigVectorType Type of the joint configuration vector.
293 /// \tparam TangentVectorType1 Type of the joint velocity vector.
294 /// \tparam TangentVectorType2 Type of the joint acceleration vector.
295 ///
296 /// \param[in] model The model structure of the rigid body system.
297 /// \param[in] data The data structure of the rigid body system.
298 /// \param[in] q The joint configuration vector (dim model.nq).
299 /// \param[in] v The joint velocity vector (dim model.nv).
300 /// \param[in] a The joint acceleration vector (dim model.nv).
301 ///
302 /// \return The joint torque regressor of the system.
303 ///
304 /// \warning This function writes temporary information in data.bodyRegressor. This means if you
305 /// have valuable data in it it will be overwritten.
306 ///
307 template<
308 typename Scalar,
309 int Options,
310 template<typename, int>
311 class JointCollectionTpl,
312 typename ConfigVectorType,
313 typename TangentVectorType1,
314 typename TangentVectorType2>
315 inline typename DataTpl<Scalar, Options, JointCollectionTpl>::MatrixXs &
316 computeJointTorqueRegressor(
317 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
318 DataTpl<Scalar, Options, JointCollectionTpl> & data,
319 const Eigen::MatrixBase<ConfigVectorType> & q,
320 const Eigen::MatrixBase<TangentVectorType1> & v,
321 const Eigen::MatrixBase<TangentVectorType2> & a);
322
323 ///
324 /// \brief Computes the kinetic energy regressor that links the kinetic energy of the system to
325 /// the dynamic parameters of each link according to the current robot motion.
326 ///
327 /// The result is stored in `data.kineticEnergyRegressor` and it corresponds to a matrix
328 /// \f$ Y_e \f$ such that \f$ K = Y_e(q,\dot{q})\pi \f$ where
329 /// \pi_i = \text{model.inertias[i].toDynamicParameters()} \f$
330 ///
331 /// \tparam JointCollection Collection of Joint types.
332 /// \tparam ConfigVectorType Type of the joint configuration vector.
333 /// \tparam TangentVectorType Type of the joint velocity vector.
334 ///
335 /// \param[in] model The model structure of the rigid body system.
336 /// \param[in] data The data structure of the rigid body system.
337 /// \param[in] q The joint configuration vector (dim model.nq).
338 /// \param[in] v The joint velocity vector (dim model.nv).
339 ///
340 /// \return The kinetic energy regressor of the system.
341 template<
342 typename Scalar,
343 int Options,
344 template<typename, int>
345 class JointCollectionTpl,
346 typename ConfigVectorType,
347 typename TangentVectorType>
348 const typename DataTpl<Scalar, Options, JointCollectionTpl>::RowVectorXs &
349 computeKineticEnergyRegressor(
350 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
351 DataTpl<Scalar, Options, JointCollectionTpl> & data,
352 const Eigen::MatrixBase<ConfigVectorType> & q,
353 const Eigen::MatrixBase<TangentVectorType> & v);
354
355 ///
356 /// \brief Computes the potential energy regressor that links the potential energy
357 /// of the system to the dynamic parameters of each link according to the current robot motion.
358 ///
359 /// The result is stored in `data.potentialEnergyRegressor` and it corresponds to a matrix
360 /// \f$ Y_p \f$ such that \f$ P = Y_p(q)\pi \f$ where
361 /// \pi_i = \text{model.inertias[i].toDynamicParameters()} \f$
362 ///
363 /// \tparam JointCollection Collection of Joint types.
364 /// \tparam ConfigVectorType Type of the joint configuration vector.
365 ///
366 /// \param[in] model The model structure of the rigid body system.
367 /// \param[in] data The data structure of the rigid body system.
368 /// \param[in] q The joint configuration vector (dim model.nq).
369 ///
370 /// \return The kinetic energy regressor of the system.
371 template<
372 typename Scalar,
373 int Options,
374 template<typename, int>
375 class JointCollectionTpl,
376 typename ConfigVectorType>
377 const typename DataTpl<Scalar, Options, JointCollectionTpl>::RowVectorXs &
378 computePotentialEnergyRegressor(
379 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
380 DataTpl<Scalar, Options, JointCollectionTpl> & data,
381 const Eigen::MatrixBase<ConfigVectorType> & q);
382 } // namespace pinocchio
383
384 /* --- Details -------------------------------------------------------------------- */
385 #include "pinocchio/algorithm/regressor.hxx"
386
387 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
388 #include "pinocchio/algorithm/regressor.txx"
389 #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
390
391 #endif // ifndef __pinocchio_algorithm_regressor_hpp__
392