crocoddyl  1.3.0
Contact RObot COntrol by Differential DYnamic programming Library (Crocoddyl)
impulse-friction-cone.hpp
1 // BSD 3-Clause License
3 //
4 // Copyright (C) 2018-2020, University of Edinburgh
5 // Copyright note valid unless otherwise stated in individual files.
6 // All rights reserved.
8 
9 #ifndef CROCODDYL_MULTIBODY_COSTS_IMPULSE_FRICTION_CONE_HPP_
10 #define CROCODDYL_MULTIBODY_COSTS_IMPULSE_FRICTION_CONE_HPP_
11 
12 #include "crocoddyl/multibody/fwd.hpp"
13 #include "crocoddyl/multibody/cost-base.hpp"
14 #include "crocoddyl/multibody/impulse-base.hpp"
15 #include "crocoddyl/multibody/impulses/impulse-3d.hpp"
16 #include "crocoddyl/multibody/impulses/impulse-6d.hpp"
17 #include "crocoddyl/multibody/data/impulses.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  CostModelImpulseFrictionConeTpl(boost::shared_ptr<StateMultibody> state,
47  boost::shared_ptr<ActivationModelAbstract> activation,
48  const FrameFrictionCone& fref);
49  CostModelImpulseFrictionConeTpl(boost::shared_ptr<StateMultibody> state, const FrameFrictionCone& fref);
51 
52  virtual void calc(const boost::shared_ptr<CostDataAbstract>& data, const Eigen::Ref<const VectorXs>& x,
53  const Eigen::Ref<const VectorXs>& u);
54  virtual void calcDiff(const boost::shared_ptr<CostDataAbstract>& data, const Eigen::Ref<const VectorXs>& x,
55  const Eigen::Ref<const VectorXs>& u);
56  virtual boost::shared_ptr<CostDataAbstract> createData(DataCollectorAbstract* const data);
57 
58  const FrameFrictionCone& get_fref() const;
59  void set_fref(const FrameFrictionCone& fref);
60 
61  protected:
62  virtual void set_referenceImpl(const std::type_info& ti, const void* pv);
63  virtual void get_referenceImpl(const std::type_info& ti, void* pv);
64 
65  using Base::activation_;
66  using Base::state_;
67  // using Base::unone_;
68 
69  private:
70  FrameFrictionCone fref_;
71 };
72 
73 template <typename _Scalar>
75  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
76 
77  typedef _Scalar Scalar;
83  typedef typename MathBase::VectorXs VectorXs;
84  typedef typename MathBase::MatrixXs MatrixXs;
85  typedef typename MathBase::Matrix6xs Matrix6xs;
86 
87  template <template <typename Scalar> class Model>
88  CostDataImpulseFrictionConeTpl(Model<Scalar>* const model, DataCollectorAbstract* const data)
89  : Base(model, data), more_than_3_constraints(false) {
90  // Check that proper shared data has been passed
92  if (d == NULL) {
93  throw_pretty("Invalid argument: the shared data should be derived from DataCollectorImpulse");
94  }
95 
96  // Avoids data casting at runtime
97  const FrameFrictionCone& fref = model->get_fref();
98  std::string frame_name = model->get_state()->get_pinocchio()->frames[fref.frame].name;
99  bool found_impulse = false;
100  for (typename ImpulseModelMultiple::ImpulseDataContainer::iterator it = d->impulses->impulses.begin();
101  it != d->impulses->impulses.end(); ++it) {
102  if (it->second->frame == fref.frame) {
103  ImpulseData3DTpl<Scalar>* d3d = dynamic_cast<ImpulseData3DTpl<Scalar>*>(it->second.get());
104  if (d3d != NULL) {
105  found_impulse = true;
106  impulse = it->second;
107  break;
108  }
109  ImpulseData6DTpl<Scalar>* d6d = dynamic_cast<ImpulseData6DTpl<Scalar>*>(it->second.get());
110  if (d6d != NULL) {
111  more_than_3_constraints = true;
112  found_impulse = true;
113  impulse = it->second;
114  break;
115  }
116  throw_pretty("Domain error: there isn't defined at least a 3d impulse for " + frame_name);
117  break;
118  }
119  }
120  if (!found_impulse) {
121  throw_pretty("Domain error: there isn't defined impulse data for " + frame_name);
122  }
123  }
124 
125  boost::shared_ptr<ImpulseDataAbstractTpl<Scalar> > impulse;
126  bool more_than_3_constraints;
127  using Base::activation;
128  using Base::cost;
129  using Base::Lx;
130  using Base::Lxx;
131  using Base::r;
132  using Base::Rx;
133  using Base::shared;
134 };
135 
136 } // namespace crocoddyl
137 
138 /* --- Details -------------------------------------------------------------- */
139 /* --- Details -------------------------------------------------------------- */
140 /* --- Details -------------------------------------------------------------- */
141 #include "crocoddyl/multibody/costs/impulse-friction-cone.hxx"
142 
143 #endif // CROCODDYL_MULTIBODY_COSTS_IMPULSE_FRICTION_CONE_HPP_