Crocoddyl
contact-wrench-cone.hpp
1 // BSD 3-Clause License
3 //
4 // Copyright (C) 2020-2025, University of Edinburgh, Heriot-Watt University
5 // Copyright note valid unless otherwise stated in individual files.
6 // All rights reserved.
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/multibody/contact-base.hpp"
14 #include "crocoddyl/multibody/contacts/contact-3d.hpp"
15 #include "crocoddyl/multibody/contacts/contact-6d.hpp"
16 #include "crocoddyl/multibody/contacts/multiple-contacts.hpp"
17 #include "crocoddyl/multibody/data/contacts.hpp"
18 #include "crocoddyl/multibody/data/impulses.hpp"
19 #include "crocoddyl/multibody/fwd.hpp"
20 #include "crocoddyl/multibody/impulse-base.hpp"
21 #include "crocoddyl/multibody/impulses/impulse-3d.hpp"
22 #include "crocoddyl/multibody/impulses/impulse-6d.hpp"
23 #include "crocoddyl/multibody/impulses/multiple-impulses.hpp"
24 #include "crocoddyl/multibody/states/multibody.hpp"
25 #include "crocoddyl/multibody/wrench-cone.hpp"
26 
27 namespace crocoddyl {
28 
53 template <typename _Scalar>
55  : public ResidualModelAbstractTpl<_Scalar> {
56  public:
57  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
59 
60  typedef _Scalar Scalar;
68  typedef typename MathBase::VectorXs VectorXs;
69  typedef typename MathBase::MatrixXs MatrixXs;
70  typedef typename MathBase::MatrixX6s MatrixX6s;
71 
85  ResidualModelContactWrenchConeTpl(std::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 
101  ResidualModelContactWrenchConeTpl(std::shared_ptr<StateMultibody> state,
102  const pinocchio::FrameIndex id,
103  const WrenchCone& fref);
104  virtual ~ResidualModelContactWrenchConeTpl() = default;
105 
118  virtual void calc(const std::shared_ptr<ResidualDataAbstract>& data,
119  const Eigen::Ref<const VectorXs>& x,
120  const Eigen::Ref<const VectorXs>& u) override;
121 
132  virtual void calc(const std::shared_ptr<ResidualDataAbstract>& data,
133  const Eigen::Ref<const VectorXs>& x) override;
134 
147  virtual void calcDiff(const std::shared_ptr<ResidualDataAbstract>& data,
148  const Eigen::Ref<const VectorXs>& x,
149  const Eigen::Ref<const VectorXs>& u) override;
150 
162  virtual void calcDiff(const std::shared_ptr<ResidualDataAbstract>& data,
163  const Eigen::Ref<const VectorXs>& x) override;
164 
171  virtual std::shared_ptr<ResidualDataAbstract> createData(
172  DataCollectorAbstract* const data) override;
173 
179  void updateJacobians(const std::shared_ptr<ResidualDataAbstract>& data);
180 
191  template <typename NewScalar>
193 
198  bool is_fwddyn() const;
199 
203  pinocchio::FrameIndex get_id() const;
204 
208  const WrenchCone& get_reference() const;
209 
213  DEPRECATED("Do not use set_id, instead create a new model",
214  void set_id(const pinocchio::FrameIndex id);)
215 
219  void set_reference(const WrenchCone& reference);
220 
226  virtual void print(std::ostream& os) const override;
227 
228  protected:
229  using Base::nu_;
230  using Base::state_;
231 
232  private:
233  bool fwddyn_;
235  bool update_jacobians_;
237  pinocchio::FrameIndex id_;
238  WrenchCone fref_;
239 };
240 
241 template <typename _Scalar>
243  : public ResidualDataAbstractTpl<_Scalar> {
244  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
245 
246  typedef _Scalar Scalar;
253  typedef typename MathBase::MatrixXs MatrixXs;
254 
255  template <template <typename Scalar> class Model>
256  ResidualDataContactWrenchConeTpl(Model<Scalar>* const model,
257  DataCollectorAbstract* const data)
258  : Base(model, data) {
259  // Check that proper shared data has been passed
260  bool is_contact = true;
262  dynamic_cast<DataCollectorContactTpl<Scalar>*>(shared);
264  dynamic_cast<DataCollectorImpulseTpl<Scalar>*>(shared);
265  if (d1 == NULL && d2 == NULL) {
266  throw_pretty(
267  "Invalid argument: the shared data should be derived from "
268  "DataCollectorContact or DataCollectorImpulse");
269  }
270  if (d2 != NULL) {
271  is_contact = false;
272  }
273 
274  // Avoids data casting at runtime
275  const pinocchio::FrameIndex id = model->get_id();
276  const std::shared_ptr<StateMultibody>& state =
277  std::static_pointer_cast<StateMultibody>(model->get_state());
278  std::string frame_name = state->get_pinocchio()->frames[id].name;
279  bool found_contact = false;
280  if (is_contact) {
281  for (typename ContactModelMultiple::ContactDataContainer::iterator it =
282  d1->contacts->contacts.begin();
283  it != d1->contacts->contacts.end(); ++it) {
284  if (it->second->frame == id) {
286  dynamic_cast<ContactData3DTpl<Scalar>*>(it->second.get());
287  if (d3d != NULL) {
288  found_contact = true;
289  contact = it->second;
290  throw_pretty(
291  "Domain error: there isn't defined at least a 6d contact for " +
292  frame_name);
293  break;
294  }
296  dynamic_cast<ContactData6DTpl<Scalar>*>(it->second.get());
297  if (d6d != NULL) {
298  found_contact = true;
299  contact = it->second;
300  break;
301  }
302  throw_pretty(
303  "Domain error: there isn't defined at least a 6d contact for " +
304  frame_name);
305  break;
306  }
307  }
308  } else {
309  for (typename ImpulseModelMultiple::ImpulseDataContainer::iterator it =
310  d2->impulses->impulses.begin();
311  it != d2->impulses->impulses.end(); ++it) {
312  if (it->second->frame == id) {
314  dynamic_cast<ImpulseData3DTpl<Scalar>*>(it->second.get());
315  if (d3d != NULL) {
316  found_contact = true;
317  contact = it->second;
318  throw_pretty(
319  "Domain error: there isn't defined at least a 6d contact for " +
320  frame_name);
321  break;
322  }
324  dynamic_cast<ImpulseData6DTpl<Scalar>*>(it->second.get());
325  if (d6d != NULL) {
326  found_contact = true;
327  contact = it->second;
328  break;
329  }
330  throw_pretty(
331  "Domain error: there isn't defined at least a 6d contact for " +
332  frame_name);
333  break;
334  }
335  }
336  }
337  if (!found_contact) {
338  throw_pretty("Domain error: there isn't defined contact data for " +
339  frame_name);
340  }
341  }
342  virtual ~ResidualDataContactWrenchConeTpl() = default;
343 
344  std::shared_ptr<ForceDataAbstractTpl<Scalar> >
346  using Base::r;
347  using Base::Ru;
348  using Base::Rx;
349  using Base::shared;
350 };
351 
352 } // namespace crocoddyl
353 
354 /* --- Details -------------------------------------------------------------- */
355 /* --- Details -------------------------------------------------------------- */
356 /* --- Details -------------------------------------------------------------- */
357 #include "crocoddyl/multibody/residuals/contact-wrench-cone.hxx"
358 
359 CROCODDYL_DECLARE_EXTERN_TEMPLATE_CLASS(
361 CROCODDYL_DECLARE_EXTERN_TEMPLATE_STRUCT(
363 
364 #endif // CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_WRENCH_CONE_HPP_
Define a stack of contact models.
Define a stack of impulse models.
Abstract class for residual models.
std::shared_ptr< StateAbstract > state_
State description.
std::size_t nu_
Control dimension.
Contact wrench cone residual function.
ResidualModelContactWrenchConeTpl(std::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const WrenchCone &fref)
Initialize the contact wrench cone residual model.
bool is_fwddyn() const
Indicates if we are using the forward-dynamics (true) or inverse-dynamics (false)
virtual void calc(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x) override
Compute the residual vector for nodes that depends only on the state.
ResidualModelContactWrenchConeTpl< NewScalar > cast() const
Cast the contact-wrench-cone residual model to a different scalar type.
virtual void calcDiff(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u) override
Compute the derivatives of the contact wrench cone residual.
pinocchio::FrameIndex get_id() const
Return the reference frame id.
DEPRECATED("Do not use set_id, instead create a new model", void set_id(const pinocchio::FrameIndex id);) void set_reference(const WrenchCone &reference)
Modify the reference frame id.
const WrenchCone & get_reference() const
Return the reference contact wrench cone.
void updateJacobians(const std::shared_ptr< ResidualDataAbstract > &data)
Update the Jacobians of the contact friction cone residual.
virtual void calc(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u) override
Compute the contact wrench cone residual.
virtual void print(std::ostream &os) const override
Print relevant information of the contact-wrench-cone residual.
ResidualModelContactWrenchConeTpl(std::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const WrenchCone &fref, const std::size_t nu, const bool fwddyn=true)
Initialize the contact wrench cone residual model.
virtual std::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data) override
Create the contact wrench cone residual data.
virtual void calcDiff(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x) override
Compute the Jacobian of the residual functions with respect to the state only.
State multibody representation.
Definition: multibody.hpp:34
MatrixXs Ru
Jacobian of the residual vector with respect the control.
MatrixXs Rx
Jacobian of the residual vector with respect the state.
DataCollectorAbstract * shared
Shared data allocated by the action model.
std::shared_ptr< ForceDataAbstractTpl< Scalar > > contact
Contact force data.
DataCollectorAbstract * shared
Shared data allocated by the action model.