Crocoddyl
contact-friction-cone.hpp
1 // BSD 3-Clause License
3 //
4 // Copyright (C) 2019-2024, LAAS-CNRS, University of Edinburgh,
5 // Heriot-Watt University
6 // Copyright note valid unless otherwise stated in individual files.
7 // All rights reserved.
9 
10 #ifndef CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_FRICTION_CONE_HPP_
11 #define CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_FRICTION_CONE_HPP_
12 
13 #include "crocoddyl/core/residual-base.hpp"
14 #include "crocoddyl/core/utils/exception.hpp"
15 #include "crocoddyl/multibody/contact-base.hpp"
16 #include "crocoddyl/multibody/contacts/contact-2d.hpp"
17 #include "crocoddyl/multibody/contacts/contact-3d.hpp"
18 #include "crocoddyl/multibody/contacts/contact-6d.hpp"
19 #include "crocoddyl/multibody/contacts/multiple-contacts.hpp"
20 #include "crocoddyl/multibody/data/contacts.hpp"
21 #include "crocoddyl/multibody/data/impulses.hpp"
22 #include "crocoddyl/multibody/friction-cone.hpp"
23 #include "crocoddyl/multibody/fwd.hpp"
24 #include "crocoddyl/multibody/impulse-base.hpp"
25 #include "crocoddyl/multibody/impulses/impulse-3d.hpp"
26 #include "crocoddyl/multibody/impulses/impulse-6d.hpp"
27 #include "crocoddyl/multibody/impulses/multiple-impulses.hpp"
28 #include "crocoddyl/multibody/states/multibody.hpp"
29 
30 namespace crocoddyl {
31 
59 template <typename _Scalar>
61  : public ResidualModelAbstractTpl<_Scalar> {
62  public:
63  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
64 
65  typedef _Scalar Scalar;
73  typedef typename MathBase::VectorXs VectorXs;
74  typedef typename MathBase::MatrixXs MatrixXs;
75  typedef typename MathBase::MatrixX3s MatrixX3s;
76 
90  ResidualModelContactFrictionConeTpl(boost::shared_ptr<StateMultibody> state,
91  const pinocchio::FrameIndex id,
92  const FrictionCone& fref,
93  const std::size_t nu,
94  const bool fwddyn = true);
95 
106  ResidualModelContactFrictionConeTpl(boost::shared_ptr<StateMultibody> state,
107  const pinocchio::FrameIndex id,
108  const FrictionCone& fref);
110 
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 
132  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
133  const Eigen::Ref<const VectorXs>& x);
134 
142  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
143  const Eigen::Ref<const VectorXs>& x,
144  const Eigen::Ref<const VectorXs>& u);
145 
157  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
158  const Eigen::Ref<const VectorXs>& x);
159 
163  virtual boost::shared_ptr<ResidualDataAbstract> createData(
164  DataCollectorAbstract* const data);
165 
171  void updateJacobians(const boost::shared_ptr<ResidualDataAbstract>& data);
172 
177  bool is_fwddyn() const;
178 
182  pinocchio::FrameIndex get_id() const;
183 
187  const FrictionCone& get_reference() const;
188 
192  DEPRECATED("Do not use set_id, instead create a new model",
193  void set_id(const pinocchio::FrameIndex id);)
194 
198  void set_reference(const FrictionCone& reference);
199 
205  virtual void print(std::ostream& os) const;
206 
207  protected:
208  using Base::nu_;
209  using Base::state_;
210 
211  private:
212  bool fwddyn_;
214  bool update_jacobians_;
216  pinocchio::FrameIndex id_;
217  FrictionCone fref_;
218 };
219 
220 template <typename _Scalar>
222  : public ResidualDataAbstractTpl<_Scalar> {
223  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
224 
225  typedef _Scalar Scalar;
232  typedef typename MathBase::MatrixXs MatrixXs;
233 
234  template <template <typename Scalar> class Model>
235  ResidualDataContactFrictionConeTpl(Model<Scalar>* const model,
236  DataCollectorAbstract* const data)
237  : Base(model, data) {
238  contact_type = ContactUndefined;
239  // Check that proper shared data has been passed
240  bool is_contact = true;
242  dynamic_cast<DataCollectorContactTpl<Scalar>*>(shared);
244  dynamic_cast<DataCollectorImpulseTpl<Scalar>*>(shared);
245  if (d1 == NULL && d2 == NULL) {
246  throw_pretty(
247  "Invalid argument: the shared data should be derived from "
248  "DataCollectorContact or DataCollectorImpulse");
249  }
250  if (d2 != NULL) {
251  is_contact = false;
252  }
253 
254  // Avoids data casting at runtime
255  const pinocchio::FrameIndex id = model->get_id();
256  const boost::shared_ptr<StateMultibody>& state =
257  boost::static_pointer_cast<StateMultibody>(model->get_state());
258  std::string frame_name = state->get_pinocchio()->frames[id].name;
259  bool found_contact = false;
260  if (is_contact) {
261  for (typename ContactModelMultiple::ContactDataContainer::iterator it =
262  d1->contacts->contacts.begin();
263  it != d1->contacts->contacts.end(); ++it) {
264  if (it->second->frame == id) {
266  dynamic_cast<ContactData2DTpl<Scalar>*>(it->second.get());
267  if (d2d != NULL) {
268  contact_type = Contact2D;
269  found_contact = true;
270  contact = it->second;
271  break;
272  }
274  dynamic_cast<ContactData3DTpl<Scalar>*>(it->second.get());
275  if (d3d != NULL) {
276  contact_type = Contact3D;
277  found_contact = true;
278  contact = it->second;
279  break;
280  }
282  dynamic_cast<ContactData6DTpl<Scalar>*>(it->second.get());
283  if (d6d != NULL) {
284  contact_type = Contact6D;
285  found_contact = true;
286  contact = it->second;
287  break;
288  }
289  throw_pretty(
290  "Domain error: there isn't defined at least a 2d contact for " +
291  frame_name);
292  break;
293  }
294  }
295  } else {
296  for (typename ImpulseModelMultiple::ImpulseDataContainer::iterator it =
297  d2->impulses->impulses.begin();
298  it != d2->impulses->impulses.end(); ++it) {
299  if (it->second->frame == id) {
301  dynamic_cast<ImpulseData3DTpl<Scalar>*>(it->second.get());
302  if (d3d != NULL) {
303  contact_type = Contact3D;
304  found_contact = true;
305  contact = it->second;
306  break;
307  }
309  dynamic_cast<ImpulseData6DTpl<Scalar>*>(it->second.get());
310  if (d6d != NULL) {
311  contact_type = Contact6D;
312  found_contact = true;
313  contact = it->second;
314  break;
315  }
316  throw_pretty(
317  "Domain error: there isn't defined at least a 3d contact for " +
318  frame_name);
319  break;
320  }
321  }
322  }
323  if (!found_contact) {
324  throw_pretty("Domain error: there isn't defined contact data for " +
325  frame_name);
326  }
327  }
328 
329  boost::shared_ptr<ForceDataAbstractTpl<Scalar> >
331  ContactType contact_type;
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-friction-cone.hxx"
344 
345 #endif // CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_FRICTION_CONE_HPP_
Define a stack of contact models.
Define a stack of impulse models.
Abstract class for residual models.
boost::shared_ptr< StateAbstract > state_
State description.
std::size_t nu_
Control dimension.
virtual void calc(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
Compute the residual vector for nodes that depends only on the state.
bool is_fwddyn() const
Indicates if we are using the forward-dynamics (true) or inverse-dynamics (false)
virtual void calcDiff(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
Compute the Jacobian of the residual functions with respect to the state only.
virtual void print(std::ostream &os) const
Print relevant information of the contact-friction-cone residual.
const FrictionCone & get_reference() const
Return the reference contact friction cone.
virtual void calc(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the contact friction cone residual.
DEPRECATED("Do not use set_id, instead create a new model", void set_id(const pinocchio::FrameIndex id);) void set_reference(const FrictionCone &reference)
Modify the reference frame id.
pinocchio::FrameIndex get_id() const
Return the reference frame id.
virtual void calcDiff(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the Jacobians of the contact friction cone residual.
virtual boost::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the contact friction cone residual data.
ResidualModelContactFrictionConeTpl(boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const FrictionCone &fref)
Initialize the contact friction cone residual model.
ResidualModelContactFrictionConeTpl(boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const FrictionCone &fref, const std::size_t nu, const bool fwddyn=true)
Initialize the contact friction cone residual model.
void updateJacobians(const boost::shared_ptr< ResidualDataAbstract > &data)
Update the Jacobians of the contact friction cone residual.
State multibody representation.
Definition: multibody.hpp:35
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.
boost::shared_ptr< ForceDataAbstractTpl< Scalar > > contact
Contact force data.
DataCollectorAbstract * shared
Shared data allocated by the action model.
ContactType contact_type
Type of contact (2D / 3D / 6D)