9 #ifndef CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_FRICTION_CONE_HPP_ 10 #define CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_FRICTION_CONE_HPP_ 12 #include "crocoddyl/multibody/fwd.hpp" 13 #include "crocoddyl/core/residual-base.hpp" 14 #include "crocoddyl/multibody/states/multibody.hpp" 15 #include "crocoddyl/multibody/contact-base.hpp" 16 #include "crocoddyl/multibody/impulse-base.hpp" 17 #include "crocoddyl/multibody/contacts/multiple-contacts.hpp" 18 #include "crocoddyl/multibody/contacts/contact-3d.hpp" 19 #include "crocoddyl/multibody/contacts/contact-6d.hpp" 20 #include "crocoddyl/multibody/impulses/multiple-impulses.hpp" 21 #include "crocoddyl/multibody/impulses/impulse-3d.hpp" 22 #include "crocoddyl/multibody/impulses/impulse-6d.hpp" 23 #include "crocoddyl/multibody/data/contacts.hpp" 24 #include "crocoddyl/multibody/data/impulses.hpp" 25 #include "crocoddyl/multibody/friction-cone.hpp" 26 #include "crocoddyl/core/utils/exception.hpp" 52 template <
typename _Scalar>
53 class ResidualModelContactFrictionConeTpl :
public ResidualModelAbstractTpl<_Scalar> {
55 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
57 typedef _Scalar Scalar;
58 typedef MathBaseTpl<Scalar> MathBase;
59 typedef ResidualModelAbstractTpl<Scalar> Base;
60 typedef ResidualDataContactFrictionConeTpl<Scalar> Data;
61 typedef StateMultibodyTpl<Scalar> StateMultibody;
62 typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract;
63 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
64 typedef FrictionConeTpl<Scalar> FrictionCone;
65 typedef typename MathBase::VectorXs VectorXs;
66 typedef typename MathBase::MatrixXs MatrixXs;
67 typedef typename MathBase::MatrixX3s MatrixX3s;
78 const FrictionCone& fref,
const std::size_t nu);
90 const FrictionCone& fref);
100 virtual void calc(
const boost::shared_ptr<ResidualDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x,
101 const Eigen::Ref<const VectorXs>& u);
110 virtual void calcDiff(
const boost::shared_ptr<ResidualDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x,
111 const Eigen::Ref<const VectorXs>& u);
116 virtual boost::shared_ptr<ResidualDataAbstract>
createData(DataCollectorAbstract*
const data);
121 pinocchio::FrameIndex
get_id()
const;
131 void set_id(
const pinocchio::FrameIndex
id);
143 virtual void print(std::ostream& os)
const;
151 pinocchio::FrameIndex id_;
155 template <
typename _Scalar>
156 struct ResidualDataContactFrictionConeTpl :
public ResidualDataAbstractTpl<_Scalar> {
157 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
159 typedef _Scalar Scalar;
160 typedef MathBaseTpl<Scalar> MathBase;
161 typedef ResidualDataAbstractTpl<Scalar> Base;
162 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
163 typedef ContactModelMultipleTpl<Scalar> ContactModelMultiple;
164 typedef ImpulseModelMultipleTpl<Scalar> ImpulseModelMultiple;
165 typedef StateMultibodyTpl<Scalar> StateMultibody;
166 typedef typename MathBase::MatrixXs MatrixXs;
168 template <
template <
typename Scalar>
class Model>
169 ResidualDataContactFrictionConeTpl(Model<Scalar>*
const model, DataCollectorAbstract*
const data)
170 : Base(model, data), more_than_3_constraints(false) {
172 bool is_contact =
true;
173 DataCollectorContactTpl<Scalar>* d1 =
dynamic_cast<DataCollectorContactTpl<Scalar>*
>(shared);
174 DataCollectorImpulseTpl<Scalar>* d2 =
dynamic_cast<DataCollectorImpulseTpl<Scalar>*
>(shared);
175 if (d1 == NULL && d2 == NULL) {
177 "Invalid argument: the shared data should be derived from DataCollectorContact or DataCollectorImpulse");
184 const pinocchio::FrameIndex
id = model->get_id();
185 const boost::shared_ptr<StateMultibody>& state = boost::static_pointer_cast<StateMultibody>(model->get_state());
186 std::string frame_name = state->get_pinocchio()->frames[id].name;
187 bool found_contact =
false;
189 for (
typename ContactModelMultiple::ContactDataContainer::iterator it = d1->contacts->contacts.begin();
190 it != d1->contacts->contacts.end(); ++it) {
191 if (it->second->frame ==
id) {
192 ContactData3DTpl<Scalar>* d3d =
dynamic_cast<ContactData3DTpl<Scalar>*
>(it->second.get());
194 found_contact =
true;
195 contact = it->second;
198 ContactData6DTpl<Scalar>* d6d =
dynamic_cast<ContactData6DTpl<Scalar>*
>(it->second.get());
200 more_than_3_constraints =
true;
201 found_contact =
true;
202 contact = it->second;
205 throw_pretty(
"Domain error: there isn't defined at least a 3d contact for " + frame_name);
210 for (
typename ImpulseModelMultiple::ImpulseDataContainer::iterator it = d2->impulses->impulses.begin();
211 it != d2->impulses->impulses.end(); ++it) {
212 if (it->second->frame ==
id) {
213 ImpulseData3DTpl<Scalar>* d3d =
dynamic_cast<ImpulseData3DTpl<Scalar>*
>(it->second.get());
215 found_contact =
true;
216 contact = it->second;
219 ImpulseData6DTpl<Scalar>* d6d =
dynamic_cast<ImpulseData6DTpl<Scalar>*
>(it->second.get());
221 more_than_3_constraints =
true;
222 found_contact =
true;
223 contact = it->second;
226 throw_pretty(
"Domain error: there isn't defined at least a 3d contact for " + frame_name);
231 if (!found_contact) {
232 throw_pretty(
"Domain error: there isn't defined contact data for " + frame_name);
236 boost::shared_ptr<ForceDataAbstractTpl<Scalar> >
contact;
249 #include "crocoddyl/multibody/residuals/contact-friction-cone.hxx" 251 #endif // CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_FRICTION_CONE_HPP_
std::size_t nu_
Control dimension.
boost::shared_ptr< StateAbstract > state_
State description.
VectorXs unone_
No control vector.