9 #ifndef CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_FORCE_HPP_ 10 #define CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_FORCE_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/core/utils/exception.hpp" 49 template <
typename _Scalar>
50 class ResidualModelContactForceTpl :
public ResidualModelAbstractTpl<_Scalar> {
52 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
54 typedef _Scalar Scalar;
55 typedef MathBaseTpl<Scalar> MathBase;
56 typedef ResidualModelAbstractTpl<Scalar> Base;
57 typedef ResidualDataContactForceTpl<Scalar> Data;
58 typedef StateMultibodyTpl<Scalar> StateMultibody;
59 typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract;
60 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
61 typedef pinocchio::ForceTpl<Scalar> Force;
62 typedef typename MathBase::VectorXs VectorXs;
63 typedef typename MathBase::MatrixXs MatrixXs;
75 const Force& fref,
const std::size_t nc,
const std::size_t nu);
88 const Force& fref,
const std::size_t nc);
102 virtual void calc(
const boost::shared_ptr<ResidualDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x,
103 const Eigen::Ref<const VectorXs>& u);
116 virtual void calcDiff(
const boost::shared_ptr<ResidualDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x,
117 const Eigen::Ref<const VectorXs>& u);
125 virtual boost::shared_ptr<ResidualDataAbstract>
createData(DataCollectorAbstract*
const data);
130 pinocchio::FrameIndex
get_id()
const;
140 void set_id(
const pinocchio::FrameIndex
id);
152 virtual void print(std::ostream& os)
const;
161 pinocchio::FrameIndex id_;
165 template <
typename _Scalar>
166 struct ResidualDataContactForceTpl :
public ResidualDataAbstractTpl<_Scalar> {
167 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
169 typedef _Scalar Scalar;
170 typedef MathBaseTpl<Scalar> MathBase;
171 typedef ResidualDataAbstractTpl<Scalar> Base;
172 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
173 typedef ContactModelMultipleTpl<Scalar> ContactModelMultiple;
174 typedef ImpulseModelMultipleTpl<Scalar> ImpulseModelMultiple;
175 typedef pinocchio::ForceTpl<Scalar> Force;
176 typedef StateMultibodyTpl<Scalar> StateMultibody;
177 typedef typename MathBase::MatrixXs MatrixXs;
179 template <
template <
typename Scalar>
class Model>
180 ResidualDataContactForceTpl(Model<Scalar>*
const model, DataCollectorAbstract*
const data) : Base(model, data) {
181 contact_type = ContactUndefined;
184 bool is_contact =
true;
185 DataCollectorContactTpl<Scalar>* d1 =
dynamic_cast<DataCollectorContactTpl<Scalar>*
>(shared);
186 DataCollectorImpulseTpl<Scalar>* d2 =
dynamic_cast<DataCollectorImpulseTpl<Scalar>*
>(shared);
187 if (d1 == NULL && d2 == NULL) {
189 "Invalid argument: the shared data should be derived from DataCollectorContact or DataCollectorImpulse");
196 const pinocchio::FrameIndex
id = model->get_id();
197 const boost::shared_ptr<StateMultibody>& state = boost::static_pointer_cast<StateMultibody>(model->get_state());
198 std::string frame_name = state->get_pinocchio()->frames[id].name;
199 bool found_contact =
false;
201 for (
typename ContactModelMultiple::ContactDataContainer::iterator it = d1->contacts->contacts.begin();
202 it != d1->contacts->contacts.end(); ++it) {
203 if (it->second->frame ==
id) {
204 ContactData3DTpl<Scalar>* d3d =
dynamic_cast<ContactData3DTpl<Scalar>*
>(it->second.get());
206 contact_type = Contact3D;
207 found_contact =
true;
208 contact = it->second;
211 ContactData6DTpl<Scalar>* d6d =
dynamic_cast<ContactData6DTpl<Scalar>*
>(it->second.get());
213 contact_type = Contact6D;
214 found_contact =
true;
215 contact = it->second;
218 throw_pretty(
"Domain error: there isn't defined at least a 3d contact for " + frame_name);
223 for (
typename ImpulseModelMultiple::ImpulseDataContainer::iterator it = d2->impulses->impulses.begin();
224 it != d2->impulses->impulses.end(); ++it) {
225 if (it->second->frame ==
id) {
226 ImpulseData3DTpl<Scalar>* d3d =
dynamic_cast<ImpulseData3DTpl<Scalar>*
>(it->second.get());
228 contact_type = Contact3D;
229 found_contact =
true;
230 contact = it->second;
233 ImpulseData6DTpl<Scalar>* d6d =
dynamic_cast<ImpulseData6DTpl<Scalar>*
>(it->second.get());
235 contact_type = Contact6D;
236 found_contact =
true;
237 contact = it->second;
240 throw_pretty(
"Domain error: there isn't defined at least a 3d impulse for " + frame_name);
245 if (!found_contact) {
246 throw_pretty(
"Domain error: there isn't defined contact/impulse data for " + frame_name);
250 boost::shared_ptr<ForceDataAbstractTpl<Scalar> >
contact;
263 #include "crocoddyl/multibody/residuals/contact-force.hxx" 265 #endif // CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_FORCE_HPP_
std::size_t nr_
Residual vector dimension.
std::size_t nu_
Control dimension.
boost::shared_ptr< StateAbstract > state_
State description.
VectorXs unone_
No control vector.