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, INRIA
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/core/costs/residual.hpp"
14 #include "crocoddyl/multibody/states/multibody.hpp"
15 #include "crocoddyl/multibody/residuals/contact-friction-cone.hpp"
16 #include "crocoddyl/multibody/frames.hpp"
17 #include "crocoddyl/core/utils/exception.hpp"
18 
19 namespace crocoddyl {
20 
43 template <typename _Scalar>
45  public:
46  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
47 
48  typedef _Scalar Scalar;
56  typedef typename MathBase::VectorXs VectorXs;
57 
66  CostModelContactFrictionConeTpl(boost::shared_ptr<StateMultibody> state,
67  boost::shared_ptr<ActivationModelAbstract> activation, const FrameFrictionCone& fref,
68  const std::size_t nu);
69 
79  CostModelContactFrictionConeTpl(boost::shared_ptr<StateMultibody> state,
80  boost::shared_ptr<ActivationModelAbstract> activation,
81  const FrameFrictionCone& fref);
82 
92  CostModelContactFrictionConeTpl(boost::shared_ptr<StateMultibody> state, const FrameFrictionCone& fref,
93  const std::size_t nu);
94 
104  CostModelContactFrictionConeTpl(boost::shared_ptr<StateMultibody> state, const FrameFrictionCone& fref);
106 
107  protected:
111  virtual void set_referenceImpl(const std::type_info& ti, const void* pv);
112 
116  virtual void get_referenceImpl(const std::type_info& ti, void* pv);
117 
118  using Base::activation_;
119  using Base::nu_;
120  using Base::residual_;
121  using Base::state_;
122  using Base::unone_;
123 
124  private:
125  FrameFrictionCone fref_;
126 };
127 
128 } // namespace crocoddyl
129 
130 /* --- Details -------------------------------------------------------------- */
131 /* --- Details -------------------------------------------------------------- */
132 /* --- Details -------------------------------------------------------------- */
133 #include "crocoddyl/multibody/costs/contact-friction-cone.hxx"
134 
135 #endif // CROCODDYL_MULTIBODY_COSTS_CONTACT_FRICTION_CONE_HPP_
boost::shared_ptr< ResidualModelAbstract > residual_
Residual model.
Definition: cost-base.hpp:236
Abstract class for cost models.
Definition: cost-base.hpp:49
virtual void set_referenceImpl(const std::type_info &ti, const void *pv)
Modify the contact friction cone reference.
Residual-based cost.
Definition: residual.hpp:36
virtual void get_referenceImpl(const std::type_info &ti, void *pv)
Return the contact friction cone reference.
boost::shared_ptr< ActivationModelAbstract > activation_
Activation model.
Definition: cost-base.hpp:235
State multibody representation.
Definition: fwd.hpp:300
CostModelContactFrictionConeTpl(boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ActivationModelAbstract > activation, const FrameFrictionCone &fref, const std::size_t nu)
Initialize the contact friction cone cost model.
Contact friction cone residual.
Definition: fwd.hpp:107
VectorXs unone_
No control vector.
Definition: cost-base.hpp:238
std::size_t nu_
Control dimension.
Definition: cost-base.hpp:237
boost::shared_ptr< StateAbstract > state_
State description.
Definition: cost-base.hpp:234