GCC Code Coverage Report


Directory: ./
File: include/crocoddyl/multibody/residuals/contact-cop-position.hpp
Date: 2025-03-26 19:23:43
Exec Total Coverage
Lines: 45 56 80.4%
Branches: 28 106 26.4%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // BSD 3-Clause License
3 //
4 // Copyright (C) 2020-2025, University of Duisburg-Essen,
5 // University of Edinburgh, Heriot-Watt University
6 // Copyright note valid unless otherwise stated in individual files.
7 // All rights reserved.
8 ///////////////////////////////////////////////////////////////////////////////
9
10 #ifndef CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_COP_POSITION_HPP_
11 #define CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_COP_POSITION_HPP_
12
13 #include "crocoddyl/core/residual-base.hpp"
14 #include "crocoddyl/multibody/contact-base.hpp"
15 #include "crocoddyl/multibody/contacts/contact-3d.hpp"
16 #include "crocoddyl/multibody/contacts/contact-6d.hpp"
17 #include "crocoddyl/multibody/contacts/multiple-contacts.hpp"
18 #include "crocoddyl/multibody/cop-support.hpp"
19 #include "crocoddyl/multibody/data/contacts.hpp"
20 #include "crocoddyl/multibody/data/impulses.hpp"
21 #include "crocoddyl/multibody/fwd.hpp"
22 #include "crocoddyl/multibody/impulse-base.hpp"
23 #include "crocoddyl/multibody/impulses/impulse-3d.hpp"
24 #include "crocoddyl/multibody/impulses/impulse-6d.hpp"
25 #include "crocoddyl/multibody/impulses/multiple-impulses.hpp"
26 #include "crocoddyl/multibody/states/multibody.hpp"
27
28 namespace crocoddyl {
29
30 /**
31 * @brief Center of pressure residual function
32 *
33 * It builds a residual function that bounds the center of pressure (CoP) for
34 * one contact surface to lie inside a certain geometric area defined around the
35 * reference contact frame. The residual residual vector is described as
36 * \f$\mathbf{r}=\mathbf{A}\boldsymbol{\lambda}\geq\mathbf{0}\f$, where \f[
37 * \mathbf{A}=
38 * \begin{bmatrix} 0 & 0 & X/2 & 0 & -1 & 0 \\ 0 & 0 & X/2 & 0 & 1 & 0 \\ 0
39 * & 0 & Y/2 & 1 & 0 & 0 \\ 0 & 0 & Y/2 & -1 & 0 & 0 \end{bmatrix} \f] is the
40 * inequality matrix and \f$\boldsymbol{\lambda}\f$ is the reference spatial
41 * contact force in the frame coordinate. The CoP lies inside the convex hull of
42 * the foot, see eq.(18-19) of
43 * https://hal.archives-ouvertes.fr/hal-02108449/document is we have:
44 * \f[
45 * \begin{align}\begin{split}\tau^x &\leq
46 * Yf^z \\-\tau^x &\leq Yf^z \\\tau^y &\leq Yf^z \\-\tau^y &\leq Yf^z
47 * \end{split}\end{align}
48 * \f]
49 * with \f$\boldsymbol{\lambda}= \begin{bmatrix}f^x & f^y & f^z & \tau^x &
50 * \tau^y & \tau^z \end{bmatrix}^T\f$.
51 *
52 * The residual is computed, from the residual vector \f$\mathbf{r}\f$, through
53 * an user defined activation model. Additionally, the contact frame id, the
54 * desired support region for the CoP and the inequality matrix are handled
55 * within `CoPSupportTpl`. The force vector \f$\boldsymbol{\lambda}\f$ and its
56 * derivatives are computed by `DifferentialActionModelContactFwdDynamicsTpl` or
57 * `ActionModelImpulseFwdDynamicTpl`. These values are stored in a shared data
58 * (i.e., `DataCollectorContactTpl` or `DataCollectorImpulseTpl`). Note that
59 * this residual function cannot be used with other action models.
60 *
61 * \sa `ResidualModelAbstractTpl`, `calc()`, `calcDiff()`, `createData()`,
62 * `DifferentialActionModelContactFwdDynamicsTpl`,
63 * `ActionModelImpulseFwdDynamicTpl`, `DataCollectorForceTpl`
64 */
65 template <typename _Scalar>
66 class ResidualModelContactCoPPositionTpl
67 : public ResidualModelAbstractTpl<_Scalar> {
68 public:
69 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
70 CROCODDYL_DERIVED_CAST(ResidualModelBase, ResidualModelContactCoPPositionTpl)
71
72 typedef _Scalar Scalar;
73 typedef MathBaseTpl<Scalar> MathBase;
74 typedef ResidualModelAbstractTpl<Scalar> Base;
75 typedef ResidualDataContactCoPPositionTpl<Scalar> Data;
76 typedef StateMultibodyTpl<Scalar> StateMultibody;
77 typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract;
78 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
79 typedef CoPSupportTpl<Scalar> CoPSupport;
80 typedef typename MathBase::VectorXs VectorXs;
81 typedef typename MathBase::MatrixXs MatrixXs;
82 typedef typename MathBase::Matrix46s Matrix46;
83
84 /**
85 * @brief Initialize the contact CoP residual model
86 *
87 * Note that for the inverse-dynamic cases, the control vector contains the
88 * generalized accelerations, torques, and all the contact forces.
89 *
90 * @param[in] state State of the multibody system
91 * @param[in] id Reference frame id
92 * @param[in] cref Reference support region of the CoP
93 * @param[in] nu Dimension of control vector
94 * @param[in] fwddyn Indicates that we have a forward dynamics problem (true)
95 * or inverse dynamics (false)
96 */
97 ResidualModelContactCoPPositionTpl(std::shared_ptr<StateMultibody> state,
98 const pinocchio::FrameIndex id,
99 const CoPSupport& cref,
100 const std::size_t nu,
101 const bool fwddyn = true);
102
103 /**
104 * @brief Initialize the contact CoP residual model
105 *
106 * The default `nu` value is obtained from `StateAbstractTpl::get_nv()`. Note
107 * that this constructor can be used for forward-dynamics cases only.
108 *
109 * @param[in] state State of the multibody system
110 * @param[in] id Reference frame id
111 * @param[in] cref Reference support region of the CoP
112 */
113 ResidualModelContactCoPPositionTpl(std::shared_ptr<StateMultibody> state,
114 const pinocchio::FrameIndex id,
115 const CoPSupport& cref);
116 70 virtual ~ResidualModelContactCoPPositionTpl() = default;
117
118 /**
119 * @brief Compute the contact CoP residual
120 *
121 * The CoP residual is computed based on the \f$\mathbf{A}\f$ matrix, the
122 * force vector is computed by `DifferentialActionModelContactFwdDynamicsTpl`
123 * or `ActionModelImpulseFwdDynamicTpl` which is stored in
124 * `DataCollectorContactTpl` or `DataCollectorImpulseTpl`.
125 *
126 * @param[in] data Contact CoP data
127 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
128 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
129 */
130 virtual void calc(const std::shared_ptr<ResidualDataAbstract>& data,
131 const Eigen::Ref<const VectorXs>& x,
132 const Eigen::Ref<const VectorXs>& u) override;
133
134 /**
135 * @brief Compute the residual vector for nodes that depends only on the state
136 *
137 * It updates the residual vector based on the state only (i.e., it ignores
138 * the contact forces). This function is used in the terminal nodes of an
139 * optimal control problem.
140 *
141 * @param[in] data Residual data
142 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
143 */
144 virtual void calc(const std::shared_ptr<ResidualDataAbstract>& data,
145 const Eigen::Ref<const VectorXs>& x) override;
146
147 /**
148 * @brief Compute the Jacobians of the contact CoP residual
149 *
150 * The CoP residual is computed based on the \f$\mathbf{A}\f$ matrix, the
151 * force vector is computed by `DifferentialActionModelContactFwdDynamicsTpl`
152 * or `ActionModelImpulseFwdDynamicTpl` which is stored in
153 * `DataCollectorContactTpl` or `DataCollectorImpulseTpl`.
154 *
155 * @param[in] data Contact CoP data
156 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
157 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
158 */
159 virtual void calcDiff(const std::shared_ptr<ResidualDataAbstract>& data,
160 const Eigen::Ref<const VectorXs>& x,
161 const Eigen::Ref<const VectorXs>& u) override;
162
163 /**
164 * @brief Compute the Jacobian of the residual functions with respect to the
165 * state only
166 *
167 * It updates the Jacobian of the residual function based on the state only
168 * (i.e., it ignores the contact forces). This function is used in the
169 * terminal nodes of an optimal control problem.
170 *
171 * @param[in] data Residual data
172 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
173 */
174 virtual void calcDiff(const std::shared_ptr<ResidualDataAbstract>& data,
175 const Eigen::Ref<const VectorXs>& x) override;
176
177 /**
178 * @brief Create the contact CoP residual data
179 *
180 * Each residual model has its own data that needs to be allocated.
181 * This function returns the allocated data for a predefined residual.
182 *
183 * @param[in] data Shared data (it should be of type
184 * `DataCollectorContactTpl`)
185 * @return the residual data.
186 */
187 virtual std::shared_ptr<ResidualDataAbstract> createData(
188 DataCollectorAbstract* const data) override;
189
190 /**
191 * @brief Update the Jacobians of the contact friction cone residual
192 *
193 * @param[in] data Contact friction cone residual data
194 */
195 void updateJacobians(const std::shared_ptr<ResidualDataAbstract>& data);
196
197 /**
198 * @brief Cast the contact-cop-position residual model to a different scalar
199 * type.
200 *
201 * It is useful for operations requiring different precision or scalar types.
202 *
203 * @tparam NewScalar The new scalar type to cast to.
204 * @return ResidualModelContactCoPPositionTpl<NewScalar> A residual model with
205 * the new scalar type.
206 */
207 template <typename NewScalar>
208 ResidualModelContactCoPPositionTpl<NewScalar> cast() const;
209
210 /**
211 * @brief Indicates if we are using the forward-dynamics (true) or
212 * inverse-dynamics (false)
213 */
214 bool is_fwddyn() const;
215
216 /**
217 * @brief Return the reference frame id
218 */
219 pinocchio::FrameIndex get_id() const;
220
221 /**
222 * @brief Return the reference support region of CoP
223 */
224 const CoPSupport& get_reference() const;
225
226 /**
227 * @brief Modify the reference frame id
228 */
229 DEPRECATED("Do not use set_id, instead create a new model",
230 void set_id(pinocchio::FrameIndex id);)
231
232 /**
233 * @brief Modify the reference support region of CoP
234 */
235 void set_reference(const CoPSupport& reference);
236
237 /**
238 * @brief Print relevant information of the cop-position residual
239 *
240 * @param[out] os Output stream object
241 */
242 virtual void print(std::ostream& os) const override;
243
244 protected:
245 using Base::nu_;
246 using Base::state_;
247
248 private:
249 bool fwddyn_; //!< Indicates if we are using this function for forward
250 //!< dynamics
251 bool update_jacobians_; //!< Indicates if we need to update the Jacobians
252 //!< (used for inverse dynamics case)
253 pinocchio::FrameIndex id_; //!< Reference frame id
254 CoPSupport cref_; //!< Reference support region of CoP
255 };
256
257 template <typename _Scalar>
258 struct ResidualDataContactCoPPositionTpl
259 : public ResidualDataAbstractTpl<_Scalar> {
260 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
261
262 typedef _Scalar Scalar;
263 typedef MathBaseTpl<Scalar> MathBase;
264 typedef ResidualDataAbstractTpl<Scalar> Base;
265 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
266 typedef StateMultibodyTpl<Scalar> StateMultibody;
267 typedef typename MathBase::MatrixXs MatrixXs;
268
269 template <template <typename Scalar> class Model>
270 3420 ResidualDataContactCoPPositionTpl(Model<Scalar>* const model,
271 DataCollectorAbstract* const data)
272 3420 : Base(model, data) {
273 // Check that proper shared data has been passed
274 3420 bool is_contact = true;
275 3420 DataCollectorContactTpl<Scalar>* d1 =
276
1/2
✓ Branch 0 taken 3418 times.
✗ Branch 1 not taken.
3420 dynamic_cast<DataCollectorContactTpl<Scalar>*>(shared);
277 3420 DataCollectorImpulseTpl<Scalar>* d2 =
278
1/2
✓ Branch 0 taken 3418 times.
✗ Branch 1 not taken.
3420 dynamic_cast<DataCollectorImpulseTpl<Scalar>*>(shared);
279
3/4
✓ Branch 0 taken 1692 times.
✓ Branch 1 taken 1726 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 1692 times.
3420 if (d1 == NULL && d2 == NULL) {
280 throw_pretty(
281 "Invalid argument: the shared data should be derived from "
282 "DataCollectorContact or DataCollectorImpulse");
283 }
284
2/2
✓ Branch 0 taken 1692 times.
✓ Branch 1 taken 1726 times.
3420 if (d2 != NULL) {
285 1692 is_contact = false;
286 }
287
288 // Avoids data casting at runtime
289
1/2
✓ Branch 1 taken 3418 times.
✗ Branch 2 not taken.
3420 const pinocchio::FrameIndex id = model->get_id();
290
1/2
✓ Branch 1 taken 3418 times.
✗ Branch 2 not taken.
3420 const std::shared_ptr<StateMultibody>& state =
291 std::static_pointer_cast<StateMultibody>(model->get_state());
292
2/4
✓ Branch 2 taken 3418 times.
✗ Branch 3 not taken.
✓ Branch 7 taken 3418 times.
✗ Branch 8 not taken.
3420 std::string frame_name = state->get_pinocchio()->frames[id].name;
293 3420 bool found_contact = false;
294
2/2
✓ Branch 0 taken 1726 times.
✓ Branch 1 taken 1692 times.
3420 if (is_contact) {
295 1728 for (typename ContactModelMultipleTpl<
296 Scalar>::ContactDataContainer::iterator it =
297 1728 d1->contacts->contacts.begin();
298
1/2
✓ Branch 4 taken 2588 times.
✗ Branch 5 not taken.
2590 it != d1->contacts->contacts.end(); ++it) {
299
2/2
✓ Branch 2 taken 1726 times.
✓ Branch 3 taken 862 times.
2590 if (it->second->frame == id) {
300 1728 ContactData3DTpl<Scalar>* d3d =
301
1/2
✓ Branch 2 taken 1726 times.
✗ Branch 3 not taken.
1728 dynamic_cast<ContactData3DTpl<Scalar>*>(it->second.get());
302
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 1726 times.
1728 if (d3d != NULL) {
303 found_contact = true;
304 contact = it->second;
305 throw_pretty(
306 "Domain error: there isn't defined at least a 6d contact for " +
307 frame_name);
308 break;
309 }
310 1728 ContactData6DTpl<Scalar>* d6d =
311
1/2
✓ Branch 2 taken 1726 times.
✗ Branch 3 not taken.
1728 dynamic_cast<ContactData6DTpl<Scalar>*>(it->second.get());
312
1/2
✓ Branch 0 taken 1726 times.
✗ Branch 1 not taken.
1728 if (d6d != NULL) {
313 1728 found_contact = true;
314 1728 contact = it->second;
315 1728 break;
316 }
317 throw_pretty(
318 "Domain error: there isn't defined at least a 6d contact for " +
319 frame_name);
320 break;
321 }
322 }
323 } else {
324 1692 for (typename ImpulseModelMultipleTpl<
325 Scalar>::ImpulseDataContainer::iterator it =
326 1692 d2->impulses->impulses.begin();
327
1/2
✓ Branch 4 taken 2772 times.
✗ Branch 5 not taken.
2772 it != d2->impulses->impulses.end(); ++it) {
328
2/2
✓ Branch 2 taken 1692 times.
✓ Branch 3 taken 1080 times.
2772 if (it->second->frame == id) {
329 1692 ImpulseData3DTpl<Scalar>* d3d =
330
1/2
✓ Branch 2 taken 1692 times.
✗ Branch 3 not taken.
1692 dynamic_cast<ImpulseData3DTpl<Scalar>*>(it->second.get());
331
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 1692 times.
1692 if (d3d != NULL) {
332 found_contact = true;
333 contact = it->second;
334 throw_pretty(
335 "Domain error: there isn't defined at least a 6d contact for " +
336 frame_name);
337 break;
338 }
339 1692 ImpulseData6DTpl<Scalar>* d6d =
340
1/2
✓ Branch 2 taken 1692 times.
✗ Branch 3 not taken.
1692 dynamic_cast<ImpulseData6DTpl<Scalar>*>(it->second.get());
341
1/2
✓ Branch 0 taken 1692 times.
✗ Branch 1 not taken.
1692 if (d6d != NULL) {
342 1692 found_contact = true;
343 1692 contact = it->second;
344 1692 break;
345 }
346 throw_pretty(
347 "Domain error: there isn't defined at least a 6d contact for " +
348 frame_name);
349 break;
350 }
351 }
352 }
353
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 3418 times.
3420 if (!found_contact) {
354 throw_pretty("Domain error: there isn't defined contact data for " +
355 frame_name);
356 }
357 3420 }
358 6836 virtual ~ResidualDataContactCoPPositionTpl() = default;
359
360 pinocchio::DataTpl<Scalar>* pinocchio; //!< Pinocchio data
361 std::shared_ptr<ForceDataAbstractTpl<Scalar> > contact; //!< Contact force
362 using Base::r;
363 using Base::Ru;
364 using Base::Rx;
365 using Base::shared;
366 };
367
368 } // namespace crocoddyl
369
370 /* --- Details -------------------------------------------------------------- */
371 /* --- Details -------------------------------------------------------------- */
372 /* --- Details -------------------------------------------------------------- */
373 #include "crocoddyl/multibody/residuals/contact-cop-position.hxx"
374
375 CROCODDYL_DECLARE_EXTERN_TEMPLATE_CLASS(
376 crocoddyl::ResidualModelContactCoPPositionTpl)
377 CROCODDYL_DECLARE_EXTERN_TEMPLATE_STRUCT(
378 crocoddyl::ResidualDataContactCoPPositionTpl)
379
380 #endif // CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_COP_POSITION_HPP_
381