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/core/cost-base.hpp" 14 #include "crocoddyl/multibody/states/multibody.hpp" 15 #include "crocoddyl/multibody/contact-base.hpp" 16 #include "crocoddyl/multibody/contacts/contact-3d.hpp" 17 #include "crocoddyl/multibody/contacts/contact-6d.hpp" 18 #include "crocoddyl/multibody/data/contacts.hpp" 19 #include "crocoddyl/multibody/frames.hpp" 20 #include "crocoddyl/multibody/friction-cone.hpp" 21 #include "crocoddyl/core/utils/exception.hpp" 22 #include "crocoddyl/core/utils/deprecate.hpp" 48 template <
typename _Scalar>
51 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
53 typedef _Scalar Scalar;
62 typedef typename MathBase::VectorXs VectorXs;
63 typedef typename MathBase::MatrixXs MatrixXs;
64 typedef typename MathBase::MatrixX3s MatrixX3s;
75 boost::shared_ptr<ActivationModelAbstract> activation,
const FrameFrictionCone& fref,
76 const std::size_t nu);
88 boost::shared_ptr<ActivationModelAbstract> activation,
89 const FrameFrictionCone& fref);
101 const std::size_t nu);
122 virtual void calc(
const boost::shared_ptr<CostDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x,
123 const Eigen::Ref<const VectorXs>& u);
132 virtual void calcDiff(
const boost::shared_ptr<CostDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x,
133 const Eigen::Ref<const VectorXs>& u);
138 virtual boost::shared_ptr<CostDataAbstract>
createData(DataCollectorAbstract*
const data);
157 FrameFrictionCone fref_;
160 template <
typename _Scalar>
162 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
164 typedef _Scalar Scalar;
171 typedef typename MathBase::MatrixXs MatrixXs;
173 template <
template <
typename Scalar>
class Model>
176 Arr_Ru(model->get_activation()->get_nr(), model->get_state()->get_nv()),
177 more_than_3_constraints(
false) {
183 throw_pretty(
"Invalid argument: the shared data should be derived from DataCollectorContact");
187 FrameFrictionCone fref = model->template get_reference<FrameFrictionCone>();
188 const boost::shared_ptr<StateMultibody>& state = boost::static_pointer_cast<StateMultibody>(model->get_state());
189 std::string frame_name = state->get_pinocchio()->frames[fref.id].name;
190 bool found_contact =
false;
191 for (
typename ContactModelMultiple::ContactDataContainer::iterator it = d->contacts->contacts.begin();
192 it != d->contacts->contacts.end(); ++it) {
193 if (it->second->frame == fref.id) {
196 found_contact =
true;
197 contact = it->second;
202 more_than_3_constraints =
true;
203 found_contact =
true;
204 contact = it->second;
207 throw_pretty(
"Domain error: there isn't defined at least a 3d contact for " + frame_name);
211 if (!found_contact) {
212 throw_pretty(
"Domain error: there isn't defined contact data for " + frame_name);
216 boost::shared_ptr<ContactDataAbstractTpl<Scalar> > contact;
219 bool more_than_3_constraints;
220 using Base::activation;
238 #include "crocoddyl/multibody/costs/contact-friction-cone.hxx" 240 #endif // CROCODDYL_MULTIBODY_COSTS_CONTACT_FRICTION_CONE_HPP_
Abstract class for cost models.
boost::shared_ptr< ActivationModelAbstract > activation_
Activation model.
State multibody representation.
VectorXs unone_
No control vector.
std::size_t nu_
Control dimension.
boost::shared_ptr< StateAbstract > state_
State description.