9 #ifndef CROCODDYL_MULTIBODY_COSTS_CONTACT_FRICTION_CONE_HPP_ 10 #define CROCODDYL_MULTIBODY_COSTS_CONTACT_FRICTION_CONE_HPP_ 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 #include "crocoddyl/core/utils/deprecate.hpp" 25 template <
typename _Scalar>
28 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
30 typedef _Scalar Scalar;
42 typedef typename MathBase::Vector6s Vector6s;
43 typedef typename MathBase::VectorXs VectorXs;
44 typedef typename MathBase::MatrixXs MatrixXs;
45 typedef typename MathBase::MatrixX3s MatrixX3s;
48 boost::shared_ptr<ActivationModelAbstract> activation,
const FrameFrictionCone& fref,
49 const std::size_t& nu);
51 boost::shared_ptr<ActivationModelAbstract> activation,
52 const FrameFrictionCone& fref);
54 const std::size_t& nu);
58 virtual void calc(
const boost::shared_ptr<CostDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x,
59 const Eigen::Ref<const VectorXs>& u);
60 virtual void calcDiff(
const boost::shared_ptr<CostDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x,
61 const Eigen::Ref<const VectorXs>& u);
62 virtual boost::shared_ptr<CostDataAbstract> createData(DataCollectorAbstract*
const data);
64 DEPRECATED(
"Use set_reference<FrameFrictionConeTpl<Scalar> >()",
void set_fref(
const FrameFrictionCone& fref));
65 DEPRECATED(
"Use get_reference<FrameFrictionConeTpl<Scalar> >()",
const FrameFrictionCone& get_fref()
const);
68 virtual void set_referenceImpl(
const std::type_info& ti,
const void* pv);
69 virtual void get_referenceImpl(
const std::type_info& ti,
void* pv)
const;
71 using Base::activation_;
77 FrameFrictionCone fref_;
80 template <
typename _Scalar>
82 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
84 typedef _Scalar Scalar;
90 typedef typename MathBase::VectorXs VectorXs;
91 typedef typename MathBase::MatrixXs MatrixXs;
92 typedef typename MathBase::Matrix6xs Matrix6xs;
94 template <
template <
typename Scalar>
class Model>
97 Arr_Ru(model->get_activation()->get_nr(), model->get_state()->get_nv()),
98 more_than_3_constraints(
false) {
104 throw_pretty(
"Invalid argument: the shared data should be derived from DataCollectorContact");
108 FrameFrictionCone fref = model->template get_reference<FrameFrictionCone>();
109 std::string frame_name = model->get_state()->get_pinocchio()->frames[fref.frame].name;
110 bool found_contact =
false;
111 for (
typename ContactModelMultiple::ContactDataContainer::iterator it = d->contacts->contacts.begin();
112 it != d->contacts->contacts.end(); ++it) {
113 if (it->second->frame == fref.frame) {
116 found_contact =
true;
117 contact = it->second;
122 more_than_3_constraints =
true;
123 found_contact =
true;
124 contact = it->second;
127 throw_pretty(
"Domain error: there isn't defined at least a 3d contact for " + frame_name);
131 if (!found_contact) {
132 throw_pretty(
"Domain error: there isn't defined contact data for " + frame_name);
136 boost::shared_ptr<ContactDataAbstractTpl<Scalar> > contact;
138 bool more_than_3_constraints;
139 using Base::activation;
157 #include "crocoddyl/multibody/costs/contact-friction-cone.hxx" 159 #endif // CROCODDYL_MULTIBODY_COSTS_CONTACT_FRICTION_CONE_HPP_