crocoddyl  1.3.0
Contact RObot COntrol by Differential DYnamic programming Library (Crocoddyl)
contact-friction-cone.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_FRICTION_CONE_HPP_
10 #define CROCODDYL_MULTIBODY_COSTS_CONTACT_FRICTION_CONE_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/multibody/friction-cone.hpp"
20 #include "crocoddyl/core/utils/exception.hpp"
21 
22 namespace crocoddyl {
23 
24 template <typename _Scalar>
26  public:
27  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
28 
29  typedef _Scalar Scalar;
41  typedef typename MathBase::Vector6s Vector6s;
42  typedef typename MathBase::VectorXs VectorXs;
43  typedef typename MathBase::MatrixXs MatrixXs;
44  typedef typename MathBase::MatrixX3s MatrixX3s;
45 
46  CostModelContactFrictionConeTpl(boost::shared_ptr<StateMultibody> state,
47  boost::shared_ptr<ActivationModelAbstract> activation, const FrameFrictionCone& fref,
48  const std::size_t& nu);
49  CostModelContactFrictionConeTpl(boost::shared_ptr<StateMultibody> state,
50  boost::shared_ptr<ActivationModelAbstract> activation,
51  const FrameFrictionCone& fref);
52  CostModelContactFrictionConeTpl(boost::shared_ptr<StateMultibody> state, const FrameFrictionCone& fref,
53  const std::size_t& nu);
54  CostModelContactFrictionConeTpl(boost::shared_ptr<StateMultibody> state, const FrameFrictionCone& fref);
56 
57  virtual void calc(const boost::shared_ptr<CostDataAbstract>& data, const Eigen::Ref<const VectorXs>& x,
58  const Eigen::Ref<const VectorXs>& u);
59  virtual void calcDiff(const boost::shared_ptr<CostDataAbstract>& data, const Eigen::Ref<const VectorXs>& x,
60  const Eigen::Ref<const VectorXs>& u);
61  virtual boost::shared_ptr<CostDataAbstract> createData(DataCollectorAbstract* const data);
62 
63  const FrameFrictionCone& get_fref() const;
64  void set_fref(const FrameFrictionCone& fref);
65 
66  protected:
67  virtual void set_referenceImpl(const std::type_info& ti, const void* pv);
68  virtual void get_referenceImpl(const std::type_info& ti, void* pv);
69 
70  using Base::activation_;
71  using Base::nu_;
72  using Base::state_;
73  using Base::unone_;
74 
75  private:
76  FrameFrictionCone fref_;
77 };
78 
79 template <typename _Scalar>
81  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
82 
83  typedef _Scalar Scalar;
89  typedef typename MathBase::VectorXs VectorXs;
90  typedef typename MathBase::MatrixXs MatrixXs;
91  typedef typename MathBase::Matrix6xs Matrix6xs;
92 
93  template <template <typename Scalar> class Model>
94  CostDataContactFrictionConeTpl(Model<Scalar>* const model, DataCollectorAbstract* const data)
95  : Base(model, data),
96  Arr_Ru(model->get_activation()->get_nr(), model->get_state()->get_nv()),
97  more_than_3_constraints(false) {
98  Arr_Ru.setZero();
99 
100  // Check that proper shared data has been passed
102  if (d == NULL) {
103  throw_pretty("Invalid argument: the shared data should be derived from DataCollectorContact");
104  }
105 
106  // Avoids data casting at runtime
107  const FrameFrictionCone& fref = model->get_fref();
108  std::string frame_name = model->get_state()->get_pinocchio()->frames[fref.frame].name;
109  bool found_contact = false;
110  for (typename ContactModelMultiple::ContactDataContainer::iterator it = d->contacts->contacts.begin();
111  it != d->contacts->contacts.end(); ++it) {
112  if (it->second->frame == fref.frame) {
113  ContactData3DTpl<Scalar>* d3d = dynamic_cast<ContactData3DTpl<Scalar>*>(it->second.get());
114  if (d3d != NULL) {
115  found_contact = true;
116  contact = it->second;
117  break;
118  }
119  ContactData6DTpl<Scalar>* d6d = dynamic_cast<ContactData6DTpl<Scalar>*>(it->second.get());
120  if (d6d != NULL) {
121  more_than_3_constraints = true;
122  found_contact = true;
123  contact = it->second;
124  break;
125  }
126  throw_pretty("Domain error: there isn't defined at least a 3d contact for " + frame_name);
127  break;
128  }
129  }
130  if (!found_contact) {
131  throw_pretty("Domain error: there isn't defined contact data for " + frame_name);
132  }
133  }
134 
135  boost::shared_ptr<ContactDataAbstractTpl<Scalar> > contact;
136  MatrixXs Arr_Ru;
137  bool more_than_3_constraints;
138  using Base::activation;
139  using Base::cost;
140  using Base::Lu;
141  using Base::Luu;
142  using Base::Lx;
143  using Base::Lxu;
144  using Base::Lxx;
145  using Base::r;
146  using Base::Ru;
147  using Base::Rx;
148  using Base::shared;
149 };
150 
151 } // namespace crocoddyl
152 
153 /* --- Details -------------------------------------------------------------- */
154 /* --- Details -------------------------------------------------------------- */
155 /* --- Details -------------------------------------------------------------- */
156 #include "crocoddyl/multibody/costs/contact-friction-cone.hxx"
157 
158 #endif // CROCODDYL_MULTIBODY_COSTS_CONTACT_FRICTION_CONE_HPP_