9 #ifndef CROCODDYL_MULTIBODY_COSTS_IMPULSE_FRICTION_CONE_HPP_
10 #define CROCODDYL_MULTIBODY_COSTS_IMPULSE_FRICTION_CONE_HPP_
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/core/utils/exception.hpp"
18 #include "crocoddyl/multibody/frames-deprecated.hpp"
22 #pragma GCC diagnostic push
23 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
47 template <
typename _Scalar>
50 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
52 typedef _Scalar Scalar;
58 typedef typename MathBase::VectorXs VectorXs;
68 boost::shared_ptr<ActivationModelAbstract> activation,
106 #include "crocoddyl/multibody/costs/impulse-friction-cone.hxx"
108 #pragma GCC diagnostic pop
Abstract class for cost models.
Impulse friction cone cost.
virtual void set_referenceImpl(const std::type_info &ti, const void *pv)
Modify the impulse friction cone reference.
CostModelImpulseFrictionConeTpl(boost::shared_ptr< StateMultibody > state, const FrameFrictionCone &fref)
Initialize the impulse friction cone cost model.
CostModelImpulseFrictionConeTpl(boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ActivationModelAbstract > activation, const FrameFrictionCone &fref)
Initialize the impulse friction cone cost model.
virtual void get_referenceImpl(const std::type_info &ti, void *pv)
Return the impulse friction cone reference.
boost::shared_ptr< ActivationModelAbstract > activation_
Activation model.
boost::shared_ptr< StateAbstract > state_
State description.
boost::shared_ptr< ResidualModelAbstract > residual_
Residual model.
State multibody representation.