crocoddyl  1.8.0
Contact RObot COntrol by Differential DYnamic programming Library (Crocoddyl)
contact-cop-position.hpp
1 // BSD 3-Clause License
3 //
4 // Copyright (C) 2020-2021, University of Duisburg-Essen, University of Edinburgh
5 // Copyright note valid unless otherwise stated in individual files.
6 // All rights reserved.
8 
9 #ifndef CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_COP_POSITION_HPP_
10 #define CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_COP_POSITION_HPP_
11 
12 #include "crocoddyl/multibody/fwd.hpp"
13 #include "crocoddyl/core/residual-base.hpp"
14 #include "crocoddyl/multibody/states/multibody.hpp"
15 #include "crocoddyl/multibody/contact-base.hpp"
16 #include "crocoddyl/multibody/impulse-base.hpp"
17 #include "crocoddyl/multibody/contacts/multiple-contacts.hpp"
18 #include "crocoddyl/multibody/contacts/contact-3d.hpp"
19 #include "crocoddyl/multibody/contacts/contact-6d.hpp"
20 #include "crocoddyl/multibody/impulses/multiple-impulses.hpp"
21 #include "crocoddyl/multibody/impulses/impulse-3d.hpp"
22 #include "crocoddyl/multibody/impulses/impulse-6d.hpp"
23 #include "crocoddyl/multibody/data/contacts.hpp"
24 #include "crocoddyl/multibody/data/impulses.hpp"
25 #include "crocoddyl/multibody/cop-support.hpp"
26 #include "crocoddyl/core/utils/exception.hpp"
27 
28 namespace crocoddyl {
29 
62 template <typename _Scalar>
63 class ResidualModelContactCoPPositionTpl : public ResidualModelAbstractTpl<_Scalar> {
64  public:
65  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
66 
67  typedef _Scalar Scalar;
68  typedef MathBaseTpl<Scalar> MathBase;
69  typedef ResidualModelAbstractTpl<Scalar> Base;
70  typedef ResidualDataContactCoPPositionTpl<Scalar> Data;
71  typedef StateMultibodyTpl<Scalar> StateMultibody;
72  typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract;
73  typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
74  typedef CoPSupportTpl<Scalar> CoPSupport;
75  typedef typename MathBase::VectorXs VectorXs;
76  typedef typename MathBase::MatrixXs MatrixXs;
77  typedef typename MathBase::Matrix46s Matrix46;
78 
87  ResidualModelContactCoPPositionTpl(boost::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id,
88  const CoPSupport& cref, const std::size_t nu);
89 
99  ResidualModelContactCoPPositionTpl(boost::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id,
100  const CoPSupport& cref);
102 
114  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data, const Eigen::Ref<const VectorXs>& x,
115  const Eigen::Ref<const VectorXs>& u);
116 
128  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data, const Eigen::Ref<const VectorXs>& x,
129  const Eigen::Ref<const VectorXs>& u);
130 
140  virtual boost::shared_ptr<ResidualDataAbstract> createData(DataCollectorAbstract* const data);
141 
145  pinocchio::FrameIndex get_id() const;
146 
150  const CoPSupport& get_reference() const;
151 
155  void set_id(pinocchio::FrameIndex id);
156 
160  void set_reference(const CoPSupport& reference);
161 
167  virtual void print(std::ostream& os) const;
168 
169  protected:
170  using Base::nu_;
171  using Base::state_;
172  using Base::unone_;
173 
174  private:
175  pinocchio::FrameIndex id_;
176  CoPSupport cref_;
177 };
178 
179 template <typename _Scalar>
180 struct ResidualDataContactCoPPositionTpl : public ResidualDataAbstractTpl<_Scalar> {
181  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
182 
183  typedef _Scalar Scalar;
184  typedef MathBaseTpl<Scalar> MathBase;
185  typedef ResidualDataAbstractTpl<Scalar> Base;
186  typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
187  typedef FrameCoPSupportTpl<Scalar> FrameCoPSupport;
188  typedef StateMultibodyTpl<Scalar> StateMultibody;
189  typedef typename MathBase::MatrixXs MatrixXs;
190 
191  template <template <typename Scalar> class Model>
192  ResidualDataContactCoPPositionTpl(Model<Scalar>* const model, DataCollectorAbstract* const data)
193  : Base(model, data) {
194  // Check that proper shared data has been passed
195  bool is_contact = true;
196  DataCollectorContactTpl<Scalar>* d1 = dynamic_cast<DataCollectorContactTpl<Scalar>*>(shared);
197  DataCollectorImpulseTpl<Scalar>* d2 = dynamic_cast<DataCollectorImpulseTpl<Scalar>*>(shared);
198  if (d1 == NULL && d2 == NULL) {
199  throw_pretty(
200  "Invalid argument: the shared data should be derived from DataCollectorContact or DataCollectorImpulse");
201  }
202  if (d2 != NULL) {
203  is_contact = false;
204  }
205 
206  // Avoids data casting at runtime
207  const pinocchio::FrameIndex id = model->get_id();
208  const boost::shared_ptr<StateMultibody>& state = boost::static_pointer_cast<StateMultibody>(model->get_state());
209  std::string frame_name = state->get_pinocchio()->frames[id].name;
210  bool found_contact = false;
211  if (is_contact) {
212  for (typename ContactModelMultiple::ContactDataContainer::iterator it = d1->contacts->contacts.begin();
213  it != d1->contacts->contacts.end(); ++it) {
214  if (it->second->frame == id) {
215  ContactData3DTpl<Scalar>* d3d = dynamic_cast<ContactData3DTpl<Scalar>*>(it->second.get());
216  if (d3d != NULL) {
217  found_contact = true;
218  contact = it->second;
219  throw_pretty("Domain error: there isn't defined at least a 6d contact for " + frame_name);
220  break;
221  }
222  ContactData6DTpl<Scalar>* d6d = dynamic_cast<ContactData6DTpl<Scalar>*>(it->second.get());
223  if (d6d != NULL) {
224  found_contact = true;
225  contact = it->second;
226  break;
227  }
228  throw_pretty("Domain error: there isn't defined at least a 6d contact for " + frame_name);
229  break;
230  }
231  }
232  } else {
233  for (typename ImpulseModelMultiple::ImpulseDataContainer::iterator it = d2->impulses->impulses.begin();
234  it != d2->impulses->impulses.end(); ++it) {
235  if (it->second->frame == id) {
236  ImpulseData3DTpl<Scalar>* d3d = dynamic_cast<ImpulseData3DTpl<Scalar>*>(it->second.get());
237  if (d3d != NULL) {
238  found_contact = true;
239  contact = it->second;
240  throw_pretty("Domain error: there isn't defined at least a 6d contact for " + frame_name);
241  break;
242  }
243  ImpulseData6DTpl<Scalar>* d6d = dynamic_cast<ImpulseData6DTpl<Scalar>*>(it->second.get());
244  if (d6d != NULL) {
245  found_contact = true;
246  contact = it->second;
247  break;
248  }
249  throw_pretty("Domain error: there isn't defined at least a 6d contact for " + frame_name);
250  break;
251  }
252  }
253  }
254  if (!found_contact) {
255  throw_pretty("Domain error: there isn't defined contact data for " + frame_name);
256  }
257  }
258 
259  pinocchio::DataTpl<Scalar>* pinocchio;
260  boost::shared_ptr<ForceDataAbstractTpl<Scalar> > contact;
261  using Base::r;
262  using Base::Ru;
263  using Base::Rx;
264  using Base::shared;
265 };
266 
267 } // namespace crocoddyl
268 
269 /* --- Details -------------------------------------------------------------- */
270 /* --- Details -------------------------------------------------------------- */
271 /* --- Details -------------------------------------------------------------- */
272 #include "crocoddyl/multibody/residuals/contact-cop-position.hxx"
273 
274 #endif // CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_COP_POSITION_HPP_
const CoPSupport & get_reference() const
Return the reference support region of CoP.
boost::shared_ptr< ForceDataAbstractTpl< Scalar > > contact
Contact force.
pinocchio::DataTpl< Scalar > * pinocchio
Pinocchio data.
std::size_t nu_
Control dimension.
ResidualModelContactCoPPositionTpl(boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const CoPSupport &cref, const std::size_t nu)
Initialize the contact CoP residual model.
virtual boost::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the contact CoP residual data.
void set_reference(const CoPSupport &reference)
Modify the reference support region of CoP.
virtual void calc(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the contact CoP 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 Jacobians of the contact CoP residual.
boost::shared_ptr< StateAbstract > state_
State description.
VectorXs unone_
No control vector.
void set_id(pinocchio::FrameIndex id)
Modify the reference frame id.
virtual void print(std::ostream &os) const
Print relevant information of the cop-position residual.