crocoddyl  1.5.0
Contact RObot COntrol by Differential DYnamic programming Library (Crocoddyl)
contact-force.hpp
1 // BSD 3-Clause License
3 //
4 // Copyright (C) 2018-2020, LAAS-CNRS, University of Edinburgh
5 // Copyright note valid unless otherwise stated in individual files.
6 // All rights reserved.
8 
9 #ifndef CROCODDYL_MULTIBODY_COSTS_CONTACT_FORCE_HPP_
10 #define CROCODDYL_MULTIBODY_COSTS_CONTACT_FORCE_HPP_
11 
12 #include "crocoddyl/multibody/fwd.hpp"
13 #include "crocoddyl/multibody/cost-base.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/data/contacts.hpp"
18 #include "crocoddyl/multibody/frames.hpp"
19 #include "crocoddyl/core/utils/exception.hpp"
20 #include "crocoddyl/core/utils/deprecate.hpp"
21 
22 namespace crocoddyl {
23 
44 template <typename _Scalar>
46  public:
47  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
48 
49  typedef _Scalar Scalar;
59  typedef typename MathBase::Vector6s Vector6s;
60  typedef typename MathBase::VectorXs VectorXs;
61  typedef typename MathBase::MatrixXs MatrixXs;
62 
74  CostModelContactForceTpl(boost::shared_ptr<StateMultibody> state,
75  boost::shared_ptr<ActivationModelAbstract> activation, const FrameForce& fref,
76  const std::size_t& nu);
77 
89  CostModelContactForceTpl(boost::shared_ptr<StateMultibody> state,
90  boost::shared_ptr<ActivationModelAbstract> activation, const FrameForce& fref);
91 
104  CostModelContactForceTpl(boost::shared_ptr<StateMultibody> state, const FrameForce& fref, const std::size_t& nr,
105  const std::size_t& nu);
106 
118  CostModelContactForceTpl(boost::shared_ptr<StateMultibody> state, const FrameForce& fref, const std::size_t& nr);
119 
130  CostModelContactForceTpl(boost::shared_ptr<StateMultibody> state, const FrameForce& fref);
131  virtual ~CostModelContactForceTpl();
132 
143  virtual void calc(const boost::shared_ptr<CostDataAbstract>& data, const Eigen::Ref<const VectorXs>& x,
144  const Eigen::Ref<const VectorXs>& u);
145 
156  virtual void calcDiff(const boost::shared_ptr<CostDataAbstract>& data, const Eigen::Ref<const VectorXs>& x,
157  const Eigen::Ref<const VectorXs>& u);
158 
168  virtual boost::shared_ptr<CostDataAbstract> createData(DataCollectorAbstract* const data);
169 
170  DEPRECATED("Use set_reference<FrameForceTpl<Scalar> >()", void set_fref(const FrameForce& fref));
171  DEPRECATED("Use get_reference<FrameForceTpl<Scalar> >()", const FrameForce& get_fref() const);
172 
173  protected:
178  virtual void set_referenceImpl(const std::type_info& ti, const void* pv);
179 
184  virtual void get_referenceImpl(const std::type_info& ti, void* pv) const;
185 
186  using Base::activation_;
187  using Base::nu_;
188  using Base::state_;
189  using Base::unone_;
190 
191  protected:
192  FrameForce fref_;
193 };
195 
196 template <typename _Scalar>
198  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
199 
200  typedef _Scalar Scalar;
206  typedef typename MathBase::VectorXs VectorXs;
207  typedef typename MathBase::MatrixXs MatrixXs;
208  typedef typename MathBase::Matrix6xs Matrix6xs;
209 
210  template <template <typename Scalar> class Model>
211  CostDataContactForceTpl(Model<Scalar>* const model, DataCollectorAbstract* const data)
212  : Base(model, data), Arr_Ru(model->get_activation()->get_nr(), model->get_state()->get_nv()) {
213  Arr_Ru.setZero();
214  contact_type = ContactUndefined;
215 
216  // Check that proper shared data has been passed
218  if (d == NULL) {
219  throw_pretty("Invalid argument: the shared data should be derived from DataCollectorContact");
220  }
221 
222  // Avoids data casting at runtime
223  FrameForce fref = model->template get_reference<FrameForce>();
224  std::string frame_name = model->get_state()->get_pinocchio()->frames[fref.id].name;
225  bool found_contact = false;
226  for (typename ContactModelMultiple::ContactDataContainer::iterator it = d->contacts->contacts.begin();
227  it != d->contacts->contacts.end(); ++it) {
228  if (it->second->frame == fref.id) {
229  ContactData3DTpl<Scalar>* d3d = dynamic_cast<ContactData3DTpl<Scalar>*>(it->second.get());
230  if (d3d != NULL) {
231  contact_type = Contact3D;
232  if (model->get_activation()->get_nr() != 3) {
233  throw_pretty("Domain error: nr isn't defined as 3 in the activation model for the 3d contact in " +
234  frame_name);
235  }
236  found_contact = true;
237  contact = it->second;
238  break;
239  }
240  ContactData6DTpl<Scalar>* d6d = dynamic_cast<ContactData6DTpl<Scalar>*>(it->second.get());
241  if (d6d != NULL) {
242  contact_type = Contact6D;
243  if (model->get_activation()->get_nr() != 6) {
244  throw_pretty("Domain error: nr isn't defined as 6 in the activation model for the 3d contact in " +
245  frame_name);
246  }
247  found_contact = true;
248  contact = it->second;
249  break;
250  }
251  throw_pretty("Domain error: there isn't defined at least a 3d contact for " + frame_name);
252  break;
253  }
254  }
255  if (!found_contact) {
256  throw_pretty("Domain error: there isn't defined contact data for " + frame_name);
257  }
258  }
259 
260  boost::shared_ptr<ContactDataAbstractTpl<Scalar> > contact;
261  MatrixXs Arr_Ru;
262  ContactType contact_type;
263  using Base::activation;
264  using Base::cost;
265  using Base::Lu;
266  using Base::Luu;
267  using Base::Lx;
268  using Base::Lxu;
269  using Base::Lxx;
270  using Base::r;
271  using Base::Ru;
272  using Base::Rx;
273  using Base::shared;
274 };
275 
276 } // namespace crocoddyl
277 
278 /* --- Details -------------------------------------------------------------- */
279 /* --- Details -------------------------------------------------------------- */
280 /* --- Details -------------------------------------------------------------- */
281 #include "crocoddyl/multibody/costs/contact-force.hxx"
282 
283 #endif // CROCODDYL_MULTIBODY_COSTS_CONTACT_FORCE_HPP_
Define a stack of contact models.
virtual boost::shared_ptr< CostDataAbstract > createData(DataCollectorAbstract *const data)
Create the contact force cost data.
Define a contact force cost function.
virtual void set_referenceImpl(const std::type_info &ti, const void *pv)
Return the reference spatial contact force in the contact coordinates .
virtual void calc(const boost::shared_ptr< CostDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the contact force cost.
CostModelContactForceTpl(boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ActivationModelAbstract > activation, const FrameForce &fref, const std::size_t &nu)
Initialize the contact force cost model.
virtual void calcDiff(const boost::shared_ptr< CostDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the derivatives of the contact force cost.
virtual void get_referenceImpl(const std::type_info &ti, void *pv) const
Modify the reference spatial contact force in the contact coordinates .