crocoddyl  1.8.0
Contact RObot COntrol by Differential DYnamic programming Library (Crocoddyl)
contact-friction-cone.hpp
1 // BSD 3-Clause License
3 //
4 // Copyright (C) 2019-2021, LAAS-CNRS, University of Edinburgh
5 // Copyright note valid unless otherwise stated in individual files.
6 // All rights reserved.
8 
9 #ifndef CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_FRICTION_CONE_HPP_
10 #define CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_FRICTION_CONE_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/friction-cone.hpp"
26 #include "crocoddyl/core/utils/exception.hpp"
27 
28 namespace crocoddyl {
29 
52 template <typename _Scalar>
53 class ResidualModelContactFrictionConeTpl : public ResidualModelAbstractTpl<_Scalar> {
54  public:
55  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
56 
57  typedef _Scalar Scalar;
58  typedef MathBaseTpl<Scalar> MathBase;
59  typedef ResidualModelAbstractTpl<Scalar> Base;
60  typedef ResidualDataContactFrictionConeTpl<Scalar> Data;
61  typedef StateMultibodyTpl<Scalar> StateMultibody;
62  typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract;
63  typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
64  typedef FrictionConeTpl<Scalar> FrictionCone;
65  typedef typename MathBase::VectorXs VectorXs;
66  typedef typename MathBase::MatrixXs MatrixXs;
67  typedef typename MathBase::MatrixX3s MatrixX3s;
68 
77  ResidualModelContactFrictionConeTpl(boost::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id,
78  const FrictionCone& fref, const std::size_t nu);
79 
89  ResidualModelContactFrictionConeTpl(boost::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id,
90  const FrictionCone& fref);
92 
100  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data, const Eigen::Ref<const VectorXs>& x,
101  const Eigen::Ref<const VectorXs>& u);
102 
110  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data, const Eigen::Ref<const VectorXs>& x,
111  const Eigen::Ref<const VectorXs>& u);
112 
116  virtual boost::shared_ptr<ResidualDataAbstract> createData(DataCollectorAbstract* const data);
117 
121  pinocchio::FrameIndex get_id() const;
122 
126  const FrictionCone& get_reference() const;
127 
131  void set_id(const pinocchio::FrameIndex id);
132 
136  void set_reference(const FrictionCone& reference);
137 
143  virtual void print(std::ostream& os) const;
144 
145  protected:
146  using Base::nu_;
147  using Base::state_;
148  using Base::unone_;
149 
150  private:
151  pinocchio::FrameIndex id_;
152  FrictionCone fref_;
153 };
154 
155 template <typename _Scalar>
156 struct ResidualDataContactFrictionConeTpl : public ResidualDataAbstractTpl<_Scalar> {
157  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
158 
159  typedef _Scalar Scalar;
160  typedef MathBaseTpl<Scalar> MathBase;
161  typedef ResidualDataAbstractTpl<Scalar> Base;
162  typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
163  typedef ContactModelMultipleTpl<Scalar> ContactModelMultiple;
164  typedef ImpulseModelMultipleTpl<Scalar> ImpulseModelMultiple;
165  typedef StateMultibodyTpl<Scalar> StateMultibody;
166  typedef typename MathBase::MatrixXs MatrixXs;
167 
168  template <template <typename Scalar> class Model>
169  ResidualDataContactFrictionConeTpl(Model<Scalar>* const model, DataCollectorAbstract* const data)
170  : Base(model, data), more_than_3_constraints(false) {
171  // Check that proper shared data has been passed
172  bool is_contact = true;
173  DataCollectorContactTpl<Scalar>* d1 = dynamic_cast<DataCollectorContactTpl<Scalar>*>(shared);
174  DataCollectorImpulseTpl<Scalar>* d2 = dynamic_cast<DataCollectorImpulseTpl<Scalar>*>(shared);
175  if (d1 == NULL && d2 == NULL) {
176  throw_pretty(
177  "Invalid argument: the shared data should be derived from DataCollectorContact or DataCollectorImpulse");
178  }
179  if (d2 != NULL) {
180  is_contact = false;
181  }
182 
183  // Avoids data casting at runtime
184  const pinocchio::FrameIndex id = model->get_id();
185  const boost::shared_ptr<StateMultibody>& state = boost::static_pointer_cast<StateMultibody>(model->get_state());
186  std::string frame_name = state->get_pinocchio()->frames[id].name;
187  bool found_contact = false;
188  if (is_contact) {
189  for (typename ContactModelMultiple::ContactDataContainer::iterator it = d1->contacts->contacts.begin();
190  it != d1->contacts->contacts.end(); ++it) {
191  if (it->second->frame == id) {
192  ContactData3DTpl<Scalar>* d3d = dynamic_cast<ContactData3DTpl<Scalar>*>(it->second.get());
193  if (d3d != NULL) {
194  found_contact = true;
195  contact = it->second;
196  break;
197  }
198  ContactData6DTpl<Scalar>* d6d = dynamic_cast<ContactData6DTpl<Scalar>*>(it->second.get());
199  if (d6d != NULL) {
200  more_than_3_constraints = true;
201  found_contact = true;
202  contact = it->second;
203  break;
204  }
205  throw_pretty("Domain error: there isn't defined at least a 3d contact for " + frame_name);
206  break;
207  }
208  }
209  } else {
210  for (typename ImpulseModelMultiple::ImpulseDataContainer::iterator it = d2->impulses->impulses.begin();
211  it != d2->impulses->impulses.end(); ++it) {
212  if (it->second->frame == id) {
213  ImpulseData3DTpl<Scalar>* d3d = dynamic_cast<ImpulseData3DTpl<Scalar>*>(it->second.get());
214  if (d3d != NULL) {
215  found_contact = true;
216  contact = it->second;
217  break;
218  }
219  ImpulseData6DTpl<Scalar>* d6d = dynamic_cast<ImpulseData6DTpl<Scalar>*>(it->second.get());
220  if (d6d != NULL) {
221  more_than_3_constraints = true;
222  found_contact = true;
223  contact = it->second;
224  break;
225  }
226  throw_pretty("Domain error: there isn't defined at least a 3d contact for " + frame_name);
227  break;
228  }
229  }
230  }
231  if (!found_contact) {
232  throw_pretty("Domain error: there isn't defined contact data for " + frame_name);
233  }
234  }
235 
236  boost::shared_ptr<ForceDataAbstractTpl<Scalar> > contact;
238  using Base::r;
239  using Base::Ru;
240  using Base::Rx;
241  using Base::shared;
242 };
243 
244 } // namespace crocoddyl
245 
246 /* --- Details -------------------------------------------------------------- */
247 /* --- Details -------------------------------------------------------------- */
248 /* --- Details -------------------------------------------------------------- */
249 #include "crocoddyl/multibody/residuals/contact-friction-cone.hxx"
250 
251 #endif // CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_FRICTION_CONE_HPP_
const FrictionCone & get_reference() const
Return the reference contact friction cone.
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.
boost::shared_ptr< ForceDataAbstractTpl< Scalar > > contact
Contact force data.
pinocchio::FrameIndex get_id() const
Return the reference frame id.
bool more_than_3_constraints
Label that indicates if the contact is bigger than 3D.
std::size_t nu_
Control dimension.
void set_reference(const FrictionCone &reference)
Modify the reference contact friction cone.
ResidualModelContactFrictionConeTpl(boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const FrictionCone &fref, const std::size_t nu)
Initialize the contact friction cone residual model.
boost::shared_ptr< StateAbstract > state_
State description.
void set_id(const pinocchio::FrameIndex id)
Modify the reference frame id.
VectorXs unone_
No control vector.
virtual boost::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the contact friction cone residual data.
virtual void print(std::ostream &os) const
Print relevant information of the contact-friction-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 friction cone residual.