GCC Code Coverage Report


Directory: ./
File: include/crocoddyl/multibody/residuals/contact-wrench-cone.hpp
Date: 2025-01-16 08:47:40
Exec Total Coverage
Lines: 43 53 81.1%
Branches: 25 98 25.5%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // BSD 3-Clause License
3 //
4 // Copyright (C) 2020-2024, University of Edinburgh, Heriot-Watt University
5 // Copyright note valid unless otherwise stated in individual files.
6 // All rights reserved.
7 ///////////////////////////////////////////////////////////////////////////////
8
9 #ifndef CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_WRENCH_CONE_HPP_
10 #define CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_WRENCH_CONE_HPP_
11
12 #include "crocoddyl/core/residual-base.hpp"
13 #include "crocoddyl/core/utils/exception.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/data/contacts.hpp"
19 #include "crocoddyl/multibody/data/impulses.hpp"
20 #include "crocoddyl/multibody/fwd.hpp"
21 #include "crocoddyl/multibody/impulse-base.hpp"
22 #include "crocoddyl/multibody/impulses/impulse-3d.hpp"
23 #include "crocoddyl/multibody/impulses/impulse-6d.hpp"
24 #include "crocoddyl/multibody/impulses/multiple-impulses.hpp"
25 #include "crocoddyl/multibody/states/multibody.hpp"
26 #include "crocoddyl/multibody/wrench-cone.hpp"
27
28 namespace crocoddyl {
29
30 /**
31 * @brief Contact wrench cone residual function
32 *
33 * This residual function is defined as
34 * \f$\mathbf{r}=\mathbf{A}\boldsymbol{\lambda}\f$, where \f$\mathbf{A}\f$ is
35 * the inequality matrix defined by the contact wrench cone, and
36 * \f$\boldsymbol{\lambda}\f$ is the current spatial forces. The current spatial
37 * forces \f$\boldsymbol{\lambda}\in\mathbb{R}^{nc}\f$ is computed by
38 * `DifferentialActionModelContactFwdDynamicsTpl` or
39 * `ActionModelImpulseFwdDynamicTpl`, with `nc` as the dimension of the contact.
40 *
41 * Both residual and residual Jacobians are computed analytically, where the
42 * force vector \f$\boldsymbol{\lambda}\f$ and its Jacobians
43 * \f$\left(\frac{\partial\boldsymbol{\lambda}}{\partial\mathbf{x}},
44 * \frac{\partial\boldsymbol{\lambda}}{\partial\mathbf{u}}\right)\f$ are
45 * computed by `DifferentialActionModelContactFwdDynamicsTpl` or
46 * `ActionModelImpulseFwdDynamicTpl`. These values are stored in a shared data
47 * (i.e., `DataCollectorContactTpl` or `DataCollectorImpulseTpl`). Note that
48 * this residual function cannot be used with other action models.
49 *
50 * \sa `ResidualModelAbstractTpl`, `calc()`, `calcDiff()`, `createData()`,
51 * `DifferentialActionModelContactFwdDynamicsTpl`,
52 * `ActionModelImpulseFwdDynamicTpl`, `DataCollectorForceTpl`
53 */
54 template <typename _Scalar>
55 class ResidualModelContactWrenchConeTpl
56 : public ResidualModelAbstractTpl<_Scalar> {
57 public:
58 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
59
60 typedef _Scalar Scalar;
61 typedef MathBaseTpl<Scalar> MathBase;
62 typedef ResidualModelAbstractTpl<Scalar> Base;
63 typedef ResidualDataContactWrenchConeTpl<Scalar> Data;
64 typedef StateMultibodyTpl<Scalar> StateMultibody;
65 typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract;
66 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
67 typedef WrenchConeTpl<Scalar> WrenchCone;
68 typedef typename MathBase::VectorXs VectorXs;
69 typedef typename MathBase::MatrixXs MatrixXs;
70 typedef typename MathBase::MatrixX6s MatrixX6s;
71
72 /**
73 * @brief Initialize the contact wrench cone residual model
74 *
75 * Note that for the inverse-dynamic cases, the control vector contains the
76 * generalized accelerations, torques, and all the contact forces.
77 *
78 * @param[in] state Multibody state
79 * @param[in] id Reference frame id
80 * @param[in] fref Reference contact wrench cone
81 * @param[in] nu Dimension of control vector
82 * @param[in] fwddyn Indicates that we have a forward dynamics problem (true)
83 * or inverse dynamics (false)
84 */
85 ResidualModelContactWrenchConeTpl(boost::shared_ptr<StateMultibody> state,
86 const pinocchio::FrameIndex id,
87 const WrenchCone& fref,
88 const std::size_t nu,
89 const bool fwddyn = true);
90
91 /**
92 * @brief Initialize the contact wrench cone residual model
93 *
94 * The default `nu` is obtained from `StateAbstractTpl::get_nv()`. Note that
95 * this constructor can be used for forward-dynamics cases only.
96 *
97 * @param[in] state Multibody state
98 * @param[in] id Reference frame id
99 * @param[in] fref Reference contact wrench cone
100 */
101 ResidualModelContactWrenchConeTpl(boost::shared_ptr<StateMultibody> state,
102 const pinocchio::FrameIndex id,
103 const WrenchCone& fref);
104 virtual ~ResidualModelContactWrenchConeTpl();
105
106 /**
107 * @brief Compute the contact wrench cone residual
108 *
109 * The CoP residual is computed based on the \f$\mathbf{A}\f$ matrix, the
110 * force vector is computed by `DifferentialActionModelContactFwdDynamicsTpl`
111 * or `ActionModelImpulseFwdDynamicTpl` which is stored in
112 * `DataCollectorContactTpl` or `DataCollectorImpulseTpl`.
113 *
114 * @param[in] data Contact force data
115 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
116 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
117 */
118 virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
119 const Eigen::Ref<const VectorXs>& x,
120 const Eigen::Ref<const VectorXs>& u);
121
122 /**
123 * @brief Compute the residual vector for nodes that depends only on the state
124 *
125 * It updates the residual vector based on the state only (i.e., it ignores
126 * the contact forces). This function is used in the terminal nodes of an
127 * optimal control problem.
128 *
129 * @param[in] data Residual data
130 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
131 */
132 virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
133 const Eigen::Ref<const VectorXs>& x);
134
135 /**
136 * @brief Compute the derivatives of the contact wrench cone residual
137 *
138 * The CoP residual is computed based on the \f$\mathbf{A}\f$ matrix, the
139 * force vector is computed by `DifferentialActionModelContactFwdDynamicsTpl`
140 * or `ActionModelImpulseFwdDynamicTpl` which is stored in
141 * `DataCollectorContactTpl` or `DataCollectorImpulseTpl`.
142 *
143 * @param[in] data Contact force data
144 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
145 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
146 */
147 virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
148 const Eigen::Ref<const VectorXs>& x,
149 const Eigen::Ref<const VectorXs>& u);
150
151 /**
152 * @brief Compute the Jacobian of the residual functions with respect to the
153 * state only
154 *
155 * It updates the Jacobian of the residual function based on the state only
156 * (i.e., it ignores the contact forces). This function is used in the
157 * terminal nodes of an optimal control problem.
158 *
159 * @param[in] data Residual data
160 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
161 */
162 virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
163 const Eigen::Ref<const VectorXs>& x);
164
165 /**
166 * @brief Create the contact wrench cone residual data
167 *
168 * @param[in] data shared data (it should be of type DataCollectorContactTpl)
169 * @return the residual data.
170 */
171 virtual boost::shared_ptr<ResidualDataAbstract> createData(
172 DataCollectorAbstract* const data);
173
174 /**
175 * @brief Update the Jacobians of the contact friction cone residual
176 *
177 * @param[in] data Contact friction cone residual data
178 */
179 void updateJacobians(const boost::shared_ptr<ResidualDataAbstract>& data);
180
181 /**
182 * @brief Indicates if we are using the forward-dynamics (true) or
183 * inverse-dynamics (false)
184 */
185 bool is_fwddyn() const;
186
187 /**
188 * @brief Return the reference frame id
189 */
190 pinocchio::FrameIndex get_id() const;
191
192 /**
193 * @brief Return the reference contact wrench cone
194 */
195 const WrenchCone& get_reference() const;
196
197 /**
198 * @brief Modify the reference frame id
199 */
200 DEPRECATED("Do not use set_id, instead create a new model",
201 void set_id(const pinocchio::FrameIndex id);)
202
203 /**
204 * @brief Modify the reference contact wrench cone
205 */
206 void set_reference(const WrenchCone& reference);
207
208 /**
209 * @brief Print relevant information of the contact-wrench-cone residual
210 *
211 * @param[out] os Output stream object
212 */
213 virtual void print(std::ostream& os) const;
214
215 protected:
216 using Base::nu_;
217 using Base::state_;
218
219 private:
220 bool fwddyn_; //!< Indicates if we are using this function for forward
221 //!< dynamics
222 bool update_jacobians_; //!< Indicates if we need to update the Jacobians
223 //!< (used for inverse dynamics case)
224 pinocchio::FrameIndex id_; //!< Reference frame id
225 WrenchCone fref_; //!< Reference contact wrench cone
226 };
227
228 template <typename _Scalar>
229 struct ResidualDataContactWrenchConeTpl
230 : public ResidualDataAbstractTpl<_Scalar> {
231 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
232
233 typedef _Scalar Scalar;
234 typedef MathBaseTpl<Scalar> MathBase;
235 typedef ResidualDataAbstractTpl<Scalar> Base;
236 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
237 typedef ContactModelMultipleTpl<Scalar> ContactModelMultiple;
238 typedef ImpulseModelMultipleTpl<Scalar> ImpulseModelMultiple;
239 typedef StateMultibodyTpl<Scalar> StateMultibody;
240 typedef typename MathBase::MatrixXs MatrixXs;
241
242 template <template <typename Scalar> class Model>
243 19521 ResidualDataContactWrenchConeTpl(Model<Scalar>* const model,
244 DataCollectorAbstract* const data)
245 19521 : Base(model, data) {
246 // Check that proper shared data has been passed
247 19521 bool is_contact = true;
248 19521 DataCollectorContactTpl<Scalar>* d1 =
249
1/2
✓ Branch 0 taken 19521 times.
✗ Branch 1 not taken.
19521 dynamic_cast<DataCollectorContactTpl<Scalar>*>(shared);
250 19521 DataCollectorImpulseTpl<Scalar>* d2 =
251
1/2
✓ Branch 0 taken 19521 times.
✗ Branch 1 not taken.
19521 dynamic_cast<DataCollectorImpulseTpl<Scalar>*>(shared);
252
3/4
✓ Branch 0 taken 4383 times.
✓ Branch 1 taken 15138 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 4383 times.
19521 if (d1 == NULL && d2 == NULL) {
253 throw_pretty(
254 "Invalid argument: the shared data should be derived from "
255 "DataCollectorContact or DataCollectorImpulse");
256 }
257
2/2
✓ Branch 0 taken 4383 times.
✓ Branch 1 taken 15138 times.
19521 if (d2 != NULL) {
258 4383 is_contact = false;
259 }
260
261 // Avoids data casting at runtime
262 19521 const pinocchio::FrameIndex id = model->get_id();
263 19521 const boost::shared_ptr<StateMultibody>& state =
264 boost::static_pointer_cast<StateMultibody>(model->get_state());
265
1/2
✓ Branch 5 taken 19521 times.
✗ Branch 6 not taken.
19521 std::string frame_name = state->get_pinocchio()->frames[id].name;
266 19521 bool found_contact = false;
267
2/2
✓ Branch 0 taken 15138 times.
✓ Branch 1 taken 4383 times.
19521 if (is_contact) {
268 15138 for (typename ContactModelMultiple::ContactDataContainer::iterator it =
269 15138 d1->contacts->contacts.begin();
270
1/2
✓ Branch 4 taken 29412 times.
✗ Branch 5 not taken.
29412 it != d1->contacts->contacts.end(); ++it) {
271
2/2
✓ Branch 2 taken 15138 times.
✓ Branch 3 taken 14274 times.
29412 if (it->second->frame == id) {
272 15138 ContactData3DTpl<Scalar>* d3d =
273
1/2
✓ Branch 2 taken 15138 times.
✗ Branch 3 not taken.
15138 dynamic_cast<ContactData3DTpl<Scalar>*>(it->second.get());
274
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 15138 times.
15138 if (d3d != NULL) {
275 found_contact = true;
276 contact = it->second;
277 throw_pretty(
278 "Domain error: there isn't defined at least a 6d contact for " +
279 frame_name);
280 break;
281 }
282 15138 ContactData6DTpl<Scalar>* d6d =
283
1/2
✓ Branch 2 taken 15138 times.
✗ Branch 3 not taken.
15138 dynamic_cast<ContactData6DTpl<Scalar>*>(it->second.get());
284
1/2
✓ Branch 0 taken 15138 times.
✗ Branch 1 not taken.
15138 if (d6d != NULL) {
285 15138 found_contact = true;
286 15138 contact = it->second;
287 15138 break;
288 }
289 throw_pretty(
290 "Domain error: there isn't defined at least a 6d contact for " +
291 frame_name);
292 break;
293 }
294 }
295 } else {
296 4383 for (typename ImpulseModelMultiple::ImpulseDataContainer::iterator it =
297 4383 d2->impulses->impulses.begin();
298
1/2
✓ Branch 4 taken 8154 times.
✗ Branch 5 not taken.
8154 it != d2->impulses->impulses.end(); ++it) {
299
2/2
✓ Branch 2 taken 4383 times.
✓ Branch 3 taken 3771 times.
8154 if (it->second->frame == id) {
300 4383 ImpulseData3DTpl<Scalar>* d3d =
301
1/2
✓ Branch 2 taken 4383 times.
✗ Branch 3 not taken.
4383 dynamic_cast<ImpulseData3DTpl<Scalar>*>(it->second.get());
302
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 4383 times.
4383 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 4383 ImpulseData6DTpl<Scalar>* d6d =
311
1/2
✓ Branch 2 taken 4383 times.
✗ Branch 3 not taken.
4383 dynamic_cast<ImpulseData6DTpl<Scalar>*>(it->second.get());
312
1/2
✓ Branch 0 taken 4383 times.
✗ Branch 1 not taken.
4383 if (d6d != NULL) {
313 4383 found_contact = true;
314 4383 contact = it->second;
315 4383 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 }
324
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 19521 times.
19521 if (!found_contact) {
325 throw_pretty("Domain error: there isn't defined contact data for " +
326 frame_name);
327 }
328 19521 }
329
330 boost::shared_ptr<ForceDataAbstractTpl<Scalar> >
331 contact; //!< Contact force data
332 using Base::r;
333 using Base::Ru;
334 using Base::Rx;
335 using Base::shared;
336 };
337
338 } // namespace crocoddyl
339
340 /* --- Details -------------------------------------------------------------- */
341 /* --- Details -------------------------------------------------------------- */
342 /* --- Details -------------------------------------------------------------- */
343 #include "crocoddyl/multibody/residuals/contact-wrench-cone.hxx"
344
345 #endif // CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_WRENCH_CONE_HPP_
346