Crocoddyl
contact-wrench-cone.hpp
1 // 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.
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 
54 template <typename _Scalar>
56  : public ResidualModelAbstractTpl<_Scalar> {
57  public:
58  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(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 
101  ResidualModelContactWrenchConeTpl(boost::shared_ptr<StateMultibody> state,
102  const pinocchio::FrameIndex id,
103  const WrenchCone& fref);
105 
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 
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 
162  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
163  const Eigen::Ref<const VectorXs>& x);
164 
171  virtual boost::shared_ptr<ResidualDataAbstract> createData(
172  DataCollectorAbstract* const data);
173 
179  void updateJacobians(const boost::shared_ptr<ResidualDataAbstract>& data);
180 
185  bool is_fwddyn() const;
186 
190  pinocchio::FrameIndex get_id() const;
191 
195  const WrenchCone& get_reference() const;
196 
200  DEPRECATED("Do not use set_id, instead create a new model",
201  void set_id(const pinocchio::FrameIndex id);)
202 
206  void set_reference(const WrenchCone& reference);
207 
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_;
222  bool update_jacobians_;
224  pinocchio::FrameIndex id_;
225  WrenchCone fref_;
226 };
227 
228 template <typename _Scalar>
230  : public ResidualDataAbstractTpl<_Scalar> {
231  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
232 
233  typedef _Scalar Scalar;
240  typedef typename MathBase::MatrixXs MatrixXs;
241 
242  template <template <typename Scalar> class Model>
243  ResidualDataContactWrenchConeTpl(Model<Scalar>* const model,
244  DataCollectorAbstract* const data)
245  : Base(model, data) {
246  // Check that proper shared data has been passed
247  bool is_contact = true;
249  dynamic_cast<DataCollectorContactTpl<Scalar>*>(shared);
251  dynamic_cast<DataCollectorImpulseTpl<Scalar>*>(shared);
252  if (d1 == NULL && d2 == NULL) {
253  throw_pretty(
254  "Invalid argument: the shared data should be derived from "
255  "DataCollectorContact or DataCollectorImpulse");
256  }
257  if (d2 != NULL) {
258  is_contact = false;
259  }
260 
261  // Avoids data casting at runtime
262  const pinocchio::FrameIndex id = model->get_id();
263  const boost::shared_ptr<StateMultibody>& state =
264  boost::static_pointer_cast<StateMultibody>(model->get_state());
265  std::string frame_name = state->get_pinocchio()->frames[id].name;
266  bool found_contact = false;
267  if (is_contact) {
268  for (typename ContactModelMultiple::ContactDataContainer::iterator it =
269  d1->contacts->contacts.begin();
270  it != d1->contacts->contacts.end(); ++it) {
271  if (it->second->frame == id) {
273  dynamic_cast<ContactData3DTpl<Scalar>*>(it->second.get());
274  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  }
283  dynamic_cast<ContactData6DTpl<Scalar>*>(it->second.get());
284  if (d6d != NULL) {
285  found_contact = true;
286  contact = it->second;
287  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  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  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  }
311  dynamic_cast<ImpulseData6DTpl<Scalar>*>(it->second.get());
312  if (d6d != NULL) {
313  found_contact = true;
314  contact = it->second;
315  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  if (!found_contact) {
325  throw_pretty("Domain error: there isn't defined contact data for " +
326  frame_name);
327  }
328  }
329 
330  boost::shared_ptr<ForceDataAbstractTpl<Scalar> >
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_
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.
Contact wrench cone 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.
bool is_fwddyn() const
Indicates if we are using the forward-dynamics (true) or inverse-dynamics (false)
ResidualModelContactWrenchConeTpl(boost::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 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-wrench-cone 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 wrench cone residual.
ResidualModelContactWrenchConeTpl(boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const WrenchCone &fref)
Initialize the contact wrench cone residual model.
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 wrench cone residual.
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.
virtual boost::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the contact wrench cone residual data.
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.