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-2d.hpp" 19 #include "crocoddyl/multibody/contacts/contact-3d.hpp" 20 #include "crocoddyl/multibody/contacts/contact-6d.hpp" 21 #include "crocoddyl/multibody/impulses/multiple-impulses.hpp" 22 #include "crocoddyl/multibody/impulses/impulse-3d.hpp" 23 #include "crocoddyl/multibody/impulses/impulse-6d.hpp" 24 #include "crocoddyl/multibody/data/contacts.hpp" 25 #include "crocoddyl/multibody/data/impulses.hpp" 26 #include "crocoddyl/multibody/friction-cone.hpp" 27 #include "crocoddyl/core/utils/exception.hpp" 53 template <
typename _Scalar>
54 class ResidualModelContactFrictionConeTpl :
public ResidualModelAbstractTpl<_Scalar> {
56 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
58 typedef _Scalar Scalar;
59 typedef MathBaseTpl<Scalar> MathBase;
60 typedef ResidualModelAbstractTpl<Scalar> Base;
61 typedef ResidualDataContactFrictionConeTpl<Scalar> Data;
62 typedef StateMultibodyTpl<Scalar> StateMultibody;
63 typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract;
64 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
65 typedef FrictionConeTpl<Scalar> FrictionCone;
66 typedef typename MathBase::VectorXs VectorXs;
67 typedef typename MathBase::MatrixXs MatrixXs;
68 typedef typename MathBase::MatrixX3s MatrixX3s;
79 const FrictionCone& fref,
const std::size_t nu);
91 const FrictionCone& fref);
101 virtual void calc(
const boost::shared_ptr<ResidualDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x,
102 const Eigen::Ref<const VectorXs>& u);
113 virtual void calc(
const boost::shared_ptr<ResidualDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x);
122 virtual void calcDiff(
const boost::shared_ptr<ResidualDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x,
123 const Eigen::Ref<const VectorXs>& u);
134 virtual void calcDiff(
const boost::shared_ptr<ResidualDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x);
139 virtual boost::shared_ptr<ResidualDataAbstract>
createData(DataCollectorAbstract*
const data);
144 pinocchio::FrameIndex
get_id()
const;
154 void set_id(
const pinocchio::FrameIndex
id);
166 virtual void print(std::ostream& os)
const;
174 pinocchio::FrameIndex id_;
178 template <
typename _Scalar>
179 struct ResidualDataContactFrictionConeTpl :
public ResidualDataAbstractTpl<_Scalar> {
180 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
182 typedef _Scalar Scalar;
183 typedef MathBaseTpl<Scalar> MathBase;
184 typedef ResidualDataAbstractTpl<Scalar> Base;
185 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
186 typedef ContactModelMultipleTpl<Scalar> ContactModelMultiple;
187 typedef ImpulseModelMultipleTpl<Scalar> ImpulseModelMultiple;
188 typedef StateMultibodyTpl<Scalar> StateMultibody;
189 typedef typename MathBase::MatrixXs MatrixXs;
191 template <
template <
typename Scalar>
class Model>
192 ResidualDataContactFrictionConeTpl(Model<Scalar>*
const model, DataCollectorAbstract*
const data)
193 : Base(model, data) {
194 contact_type = ContactUndefined;
196 bool is_contact =
true;
197 DataCollectorContactTpl<Scalar>* d1 =
dynamic_cast<DataCollectorContactTpl<Scalar>*
>(shared);
198 DataCollectorImpulseTpl<Scalar>* d2 =
dynamic_cast<DataCollectorImpulseTpl<Scalar>*
>(shared);
199 if (d1 == NULL && d2 == NULL) {
201 "Invalid argument: the shared data should be derived from DataCollectorContact or DataCollectorImpulse");
208 const pinocchio::FrameIndex
id = model->get_id();
209 const boost::shared_ptr<StateMultibody>& state = boost::static_pointer_cast<StateMultibody>(model->get_state());
210 std::string frame_name = state->get_pinocchio()->frames[id].name;
211 bool found_contact =
false;
213 for (
typename ContactModelMultiple::ContactDataContainer::iterator it = d1->contacts->contacts.begin();
214 it != d1->contacts->contacts.end(); ++it) {
215 if (it->second->frame ==
id) {
216 ContactData2DTpl<Scalar>* d2d =
dynamic_cast<ContactData2DTpl<Scalar>*
>(it->second.get());
218 contact_type = Contact2D;
219 found_contact =
true;
220 contact = it->second;
223 ContactData3DTpl<Scalar>* d3d =
dynamic_cast<ContactData3DTpl<Scalar>*
>(it->second.get());
225 contact_type = Contact3D;
226 found_contact =
true;
227 contact = it->second;
230 ContactData6DTpl<Scalar>* d6d =
dynamic_cast<ContactData6DTpl<Scalar>*
>(it->second.get());
232 contact_type = Contact6D;
233 found_contact =
true;
234 contact = it->second;
237 throw_pretty(
"Domain error: there isn't defined at least a 2d contact for " + frame_name);
242 for (
typename ImpulseModelMultiple::ImpulseDataContainer::iterator it = d2->impulses->impulses.begin();
243 it != d2->impulses->impulses.end(); ++it) {
244 if (it->second->frame ==
id) {
245 ImpulseData3DTpl<Scalar>* d3d =
dynamic_cast<ImpulseData3DTpl<Scalar>*
>(it->second.get());
247 contact_type = Contact3D;
248 found_contact =
true;
249 contact = it->second;
252 ImpulseData6DTpl<Scalar>* d6d =
dynamic_cast<ImpulseData6DTpl<Scalar>*
>(it->second.get());
254 contact_type = Contact6D;
255 found_contact =
true;
256 contact = it->second;
259 throw_pretty(
"Domain error: there isn't defined at least a 3d contact for " + frame_name);
264 if (!found_contact) {
265 throw_pretty(
"Domain error: there isn't defined contact data for " + frame_name);
269 boost::shared_ptr<ForceDataAbstractTpl<Scalar> >
contact;
282 #include "crocoddyl/multibody/residuals/contact-friction-cone.hxx" 284 #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.