crocoddyl  1.8.1
Contact RObot COntrol by Differential DYnamic programming Library (Crocoddyl)
contact-wrench-cone.hpp
1 // BSD 3-Clause License
3 //
4 // Copyright (C) 2020-2021, University of Edinburgh
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/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/wrench-cone.hpp"
26 #include "crocoddyl/core/utils/exception.hpp"
27 
28 namespace crocoddyl {
29 
49 template <typename _Scalar>
50 class ResidualModelContactWrenchConeTpl : public ResidualModelAbstractTpl<_Scalar> {
51  public:
52  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
53 
54  typedef _Scalar Scalar;
55  typedef MathBaseTpl<Scalar> MathBase;
56  typedef ResidualModelAbstractTpl<Scalar> Base;
57  typedef ResidualDataContactWrenchConeTpl<Scalar> Data;
58  typedef StateMultibodyTpl<Scalar> StateMultibody;
59  typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract;
60  typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
61  typedef WrenchConeTpl<Scalar> WrenchCone;
62  typedef typename MathBase::VectorXs VectorXs;
63  typedef typename MathBase::MatrixXs MatrixXs;
64  typedef typename MathBase::MatrixX6s MatrixX6s;
65 
74  ResidualModelContactWrenchConeTpl(boost::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id,
75  const WrenchCone& fref, const std::size_t nu);
76 
86  ResidualModelContactWrenchConeTpl(boost::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id,
87  const WrenchCone& fref);
89 
101  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data, const Eigen::Ref<const VectorXs>& x,
102  const Eigen::Ref<const VectorXs>& u);
103 
115  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data, const Eigen::Ref<const VectorXs>& x,
116  const Eigen::Ref<const VectorXs>& u);
117 
124  virtual boost::shared_ptr<ResidualDataAbstract> createData(DataCollectorAbstract* const data);
125 
129  pinocchio::FrameIndex get_id() const;
130 
134  const WrenchCone& get_reference() const;
135 
139  void set_id(const pinocchio::FrameIndex id);
140 
144  void set_reference(const WrenchCone& reference);
145 
151  virtual void print(std::ostream& os) const;
152 
153  protected:
154  using Base::nu_;
155  using Base::state_;
156  using Base::unone_;
157 
158  private:
159  pinocchio::FrameIndex id_;
160  WrenchCone fref_;
161 };
162 
163 template <typename _Scalar>
164 struct ResidualDataContactWrenchConeTpl : public ResidualDataAbstractTpl<_Scalar> {
165  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
166 
167  typedef _Scalar Scalar;
168  typedef MathBaseTpl<Scalar> MathBase;
169  typedef ResidualDataAbstractTpl<Scalar> Base;
170  typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
171  typedef ContactModelMultipleTpl<Scalar> ContactModelMultiple;
172  typedef ImpulseModelMultipleTpl<Scalar> ImpulseModelMultiple;
173  typedef StateMultibodyTpl<Scalar> StateMultibody;
174  typedef typename MathBase::MatrixXs MatrixXs;
175 
176  template <template <typename Scalar> class Model>
177  ResidualDataContactWrenchConeTpl(Model<Scalar>* const model, DataCollectorAbstract* const data) : Base(model, data) {
178  // Check that proper shared data has been passed
179  bool is_contact = true;
180  DataCollectorContactTpl<Scalar>* d1 = dynamic_cast<DataCollectorContactTpl<Scalar>*>(shared);
181  DataCollectorImpulseTpl<Scalar>* d2 = dynamic_cast<DataCollectorImpulseTpl<Scalar>*>(shared);
182  if (d1 == NULL && d2 == NULL) {
183  throw_pretty(
184  "Invalid argument: the shared data should be derived from DataCollectorContact or DataCollectorImpulse");
185  }
186  if (d2 != NULL) {
187  is_contact = false;
188  }
189 
190  // Avoids data casting at runtime
191  const pinocchio::FrameIndex id = model->get_id();
192  const boost::shared_ptr<StateMultibody>& state = boost::static_pointer_cast<StateMultibody>(model->get_state());
193  std::string frame_name = state->get_pinocchio()->frames[id].name;
194  bool found_contact = false;
195  if (is_contact) {
196  for (typename ContactModelMultiple::ContactDataContainer::iterator it = d1->contacts->contacts.begin();
197  it != d1->contacts->contacts.end(); ++it) {
198  if (it->second->frame == id) {
199  ContactData3DTpl<Scalar>* d3d = dynamic_cast<ContactData3DTpl<Scalar>*>(it->second.get());
200  if (d3d != NULL) {
201  found_contact = true;
202  contact = it->second;
203  throw_pretty("Domain error: there isn't defined at least a 6d contact for " + frame_name);
204  break;
205  }
206  ContactData6DTpl<Scalar>* d6d = dynamic_cast<ContactData6DTpl<Scalar>*>(it->second.get());
207  if (d6d != NULL) {
208  found_contact = true;
209  contact = it->second;
210  break;
211  }
212  throw_pretty("Domain error: there isn't defined at least a 6d contact for " + frame_name);
213  break;
214  }
215  }
216  } else {
217  for (typename ImpulseModelMultiple::ImpulseDataContainer::iterator it = d2->impulses->impulses.begin();
218  it != d2->impulses->impulses.end(); ++it) {
219  if (it->second->frame == id) {
220  ImpulseData3DTpl<Scalar>* d3d = dynamic_cast<ImpulseData3DTpl<Scalar>*>(it->second.get());
221  if (d3d != NULL) {
222  found_contact = true;
223  contact = it->second;
224  throw_pretty("Domain error: there isn't defined at least a 6d contact for " + frame_name);
225  break;
226  }
227  ImpulseData6DTpl<Scalar>* d6d = dynamic_cast<ImpulseData6DTpl<Scalar>*>(it->second.get());
228  if (d6d != NULL) {
229  found_contact = true;
230  contact = it->second;
231  break;
232  }
233  throw_pretty("Domain error: there isn't defined at least a 6d contact for " + frame_name);
234  break;
235  }
236  }
237  }
238  if (!found_contact) {
239  throw_pretty("Domain error: there isn't defined contact data for " + frame_name);
240  }
241  }
242 
243  boost::shared_ptr<ForceDataAbstractTpl<Scalar> > contact;
244  using Base::r;
245  using Base::Ru;
246  using Base::Rx;
247  using Base::shared;
248 };
249 
250 } // namespace crocoddyl
251 
252 /* --- Details -------------------------------------------------------------- */
253 /* --- Details -------------------------------------------------------------- */
254 /* --- Details -------------------------------------------------------------- */
255 #include "crocoddyl/multibody/residuals/contact-wrench-cone.hxx"
256 
257 #endif // CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_WRENCH_CONE_HPP_
virtual void print(std::ostream &os) const
Print relevant information of the contact-wrench-cone residual.
pinocchio::FrameIndex get_id() const
Return the reference frame id.
void set_id(const pinocchio::FrameIndex id)
Modify the reference frame id.
std::size_t nu_
Control dimension.
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.
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.
boost::shared_ptr< StateAbstract > state_
State description.
VectorXs unone_
No control vector.
ResidualModelContactWrenchConeTpl(boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const WrenchCone &fref, const std::size_t nu)
Initialize the contact wrench cone residual model.
const WrenchCone & get_reference() const
Return the reference contact wrench cone.
void set_reference(const WrenchCone &reference)
Modify the reference contact wrench cone.
boost::shared_ptr< ForceDataAbstractTpl< Scalar > > contact
Contact force data.
virtual boost::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the contact wrench cone residual data.