Crocoddyl
contact-force.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_FORCE_HPP_
11 #define CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_FORCE_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-1d.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/fwd.hpp"
23 #include "crocoddyl/multibody/impulse-base.hpp"
24 #include "crocoddyl/multibody/impulses/impulse-3d.hpp"
25 #include "crocoddyl/multibody/impulses/impulse-6d.hpp"
26 #include "crocoddyl/multibody/impulses/multiple-impulses.hpp"
27 #include "crocoddyl/multibody/states/multibody.hpp"
28 
29 namespace crocoddyl {
30 
56 template <typename _Scalar>
58  public:
59  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
60 
61  typedef _Scalar Scalar;
68  typedef pinocchio::ForceTpl<Scalar> Force;
69  typedef typename MathBase::VectorXs VectorXs;
70  typedef typename MathBase::MatrixXs MatrixXs;
71 
87  ResidualModelContactForceTpl(boost::shared_ptr<StateMultibody> state,
88  const pinocchio::FrameIndex id,
89  const Force& fref, const std::size_t nc,
90  const std::size_t nu, const bool fwddyn = true);
91 
104  ResidualModelContactForceTpl(boost::shared_ptr<StateMultibody> state,
105  const pinocchio::FrameIndex id,
106  const Force& fref, const std::size_t nc);
107  virtual ~ResidualModelContactForceTpl();
108 
121  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
122  const Eigen::Ref<const VectorXs>& x,
123  const Eigen::Ref<const VectorXs>& u);
124 
135  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
136  const Eigen::Ref<const VectorXs>& x);
137 
150  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
151  const Eigen::Ref<const VectorXs>& x,
152  const Eigen::Ref<const VectorXs>& u);
153 
165  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
166  const Eigen::Ref<const VectorXs>& x);
167 
174  virtual boost::shared_ptr<ResidualDataAbstract> createData(
175  DataCollectorAbstract* const data);
176 
182  void updateJacobians(const boost::shared_ptr<ResidualDataAbstract>& data);
183 
188  bool is_fwddyn() const;
189 
193  pinocchio::FrameIndex get_id() const;
194 
199  const Force& get_reference() const;
200 
204  DEPRECATED("Do not use set_id, instead create a new model",
205  void set_id(const pinocchio::FrameIndex id);)
206 
211  void set_reference(const Force& reference);
212 
218  virtual void print(std::ostream& os) const;
219 
220  protected:
221  using Base::nr_;
222  using Base::nu_;
223  using Base::state_;
224 
225  private:
226  bool fwddyn_;
228  bool update_jacobians_;
230  pinocchio::FrameIndex id_;
231  Force fref_;
232 };
233 
234 template <typename _Scalar>
236  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
237 
238  typedef _Scalar Scalar;
244  typedef pinocchio::ForceTpl<Scalar> Force;
246  typedef typename MathBase::MatrixXs MatrixXs;
247 
248  template <template <typename Scalar> class Model>
249  ResidualDataContactForceTpl(Model<Scalar>* const model,
250  DataCollectorAbstract* const data)
251  : Base(model, data) {
252  contact_type = ContactUndefined;
253 
254  // Check that proper shared data has been passed
255  bool is_contact = true;
257  dynamic_cast<DataCollectorContactTpl<Scalar>*>(shared);
259  dynamic_cast<DataCollectorImpulseTpl<Scalar>*>(shared);
260  if (d1 == NULL && d2 == NULL) {
261  throw_pretty(
262  "Invalid argument: the shared data should be derived from "
263  "DataCollectorContact or DataCollectorImpulse");
264  }
265  if (d2 != NULL) {
266  is_contact = false;
267  }
268 
269  // Avoids data casting at runtime
270  const pinocchio::FrameIndex id = model->get_id();
271  const boost::shared_ptr<StateMultibody>& state =
272  boost::static_pointer_cast<StateMultibody>(model->get_state());
273  std::string frame_name = state->get_pinocchio()->frames[id].name;
274  bool found_contact = false;
275  if (is_contact) {
276  for (typename ContactModelMultiple::ContactDataContainer::iterator it =
277  d1->contacts->contacts.begin();
278  it != d1->contacts->contacts.end(); ++it) {
279  if (it->second->frame == id) {
281  dynamic_cast<ContactData1DTpl<Scalar>*>(it->second.get());
282  if (d1d != NULL) {
283  contact_type = Contact1D;
284  found_contact = true;
285  contact = it->second;
286  break;
287  }
289  dynamic_cast<ContactData3DTpl<Scalar>*>(it->second.get());
290  if (d3d != NULL) {
291  contact_type = Contact3D;
292  found_contact = true;
293  contact = it->second;
294  break;
295  }
297  dynamic_cast<ContactData6DTpl<Scalar>*>(it->second.get());
298  if (d6d != NULL) {
299  contact_type = Contact6D;
300  found_contact = true;
301  contact = it->second;
302  break;
303  }
304  throw_pretty(
305  "Domain error: there isn't defined at least a 3d contact for " +
306  frame_name);
307  break;
308  }
309  }
310  } else {
311  for (typename ImpulseModelMultiple::ImpulseDataContainer::iterator it =
312  d2->impulses->impulses.begin();
313  it != d2->impulses->impulses.end(); ++it) {
314  if (it->second->frame == id) {
316  dynamic_cast<ImpulseData3DTpl<Scalar>*>(it->second.get());
317  if (d3d != NULL) {
318  contact_type = Contact3D;
319  found_contact = true;
320  contact = it->second;
321  break;
322  }
324  dynamic_cast<ImpulseData6DTpl<Scalar>*>(it->second.get());
325  if (d6d != NULL) {
326  contact_type = Contact6D;
327  found_contact = true;
328  contact = it->second;
329  break;
330  }
331  throw_pretty(
332  "Domain error: there isn't defined at least a 3d impulse for " +
333  frame_name);
334  break;
335  }
336  }
337  }
338  if (!found_contact) {
339  throw_pretty(
340  "Domain error: there isn't defined contact/impulse data for " +
341  frame_name);
342  }
343  }
344 
345  boost::shared_ptr<ForceDataAbstractTpl<Scalar> >
347  ContactType contact_type;
348  using Base::r;
349  using Base::Ru;
350  using Base::Rx;
351  using Base::shared;
352 };
353 
354 } // namespace crocoddyl
355 
356 /* --- Details -------------------------------------------------------------- */
357 /* --- Details -------------------------------------------------------------- */
358 /* --- Details -------------------------------------------------------------- */
359 #include "crocoddyl/multibody/residuals/contact-force.hxx"
360 
361 #endif // CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_FORCE_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.
std::size_t nr_
Residual vector dimension.
Define a contact force residual function.
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.
ResidualModelContactForceTpl(boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const Force &fref, const std::size_t nc, const std::size_t nu, const bool fwddyn=true)
Initialize the contact force residual model.
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-force residual.
virtual void calc(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the contact force residual.
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 derivatives of the contact force residual.
const Force & get_reference() const
Return the reference spatial contact force in the contact coordinates.
virtual boost::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the contact force residual data.
void updateJacobians(const boost::shared_ptr< ResidualDataAbstract > &data)
Update the Jacobians of 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 Force &reference)
Modify the reference frame id.
ResidualModelContactForceTpl(boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const Force &fref, const std::size_t nc)
Initialize the contact force residual model.
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 (3D / 6D)