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-1d.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/core/utils/exception.hpp" 50 template <
typename _Scalar>
51 class ResidualModelContactForceTpl :
public ResidualModelAbstractTpl<_Scalar> {
53 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
55 typedef _Scalar Scalar;
56 typedef MathBaseTpl<Scalar> MathBase;
57 typedef ResidualModelAbstractTpl<Scalar> Base;
58 typedef ResidualDataContactForceTpl<Scalar> Data;
59 typedef StateMultibodyTpl<Scalar> StateMultibody;
60 typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract;
61 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
62 typedef pinocchio::ForceTpl<Scalar> Force;
63 typedef typename MathBase::VectorXs VectorXs;
64 typedef typename MathBase::MatrixXs MatrixXs;
76 const Force& fref,
const std::size_t nc,
const std::size_t nu);
89 const Force& fref,
const std::size_t nc);
103 virtual void calc(
const boost::shared_ptr<ResidualDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x,
104 const Eigen::Ref<const VectorXs>& u);
115 virtual void calc(
const boost::shared_ptr<ResidualDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x);
128 virtual void calcDiff(
const boost::shared_ptr<ResidualDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x,
129 const Eigen::Ref<const VectorXs>& u);
140 virtual void calcDiff(
const boost::shared_ptr<ResidualDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x);
148 virtual boost::shared_ptr<ResidualDataAbstract>
createData(DataCollectorAbstract*
const data);
153 pinocchio::FrameIndex
get_id()
const;
163 void set_id(
const pinocchio::FrameIndex
id);
175 virtual void print(std::ostream& os)
const;
184 pinocchio::FrameIndex id_;
188 template <
typename _Scalar>
189 struct ResidualDataContactForceTpl :
public ResidualDataAbstractTpl<_Scalar> {
190 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
192 typedef _Scalar Scalar;
193 typedef MathBaseTpl<Scalar> MathBase;
194 typedef ResidualDataAbstractTpl<Scalar> Base;
195 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
196 typedef ContactModelMultipleTpl<Scalar> ContactModelMultiple;
197 typedef ImpulseModelMultipleTpl<Scalar> ImpulseModelMultiple;
198 typedef pinocchio::ForceTpl<Scalar> Force;
199 typedef StateMultibodyTpl<Scalar> StateMultibody;
200 typedef typename MathBase::MatrixXs MatrixXs;
202 template <
template <
typename Scalar>
class Model>
203 ResidualDataContactForceTpl(Model<Scalar>*
const model, DataCollectorAbstract*
const data) : Base(model, data) {
207 bool is_contact =
true;
208 DataCollectorContactTpl<Scalar>* d1 =
dynamic_cast<DataCollectorContactTpl<Scalar>*
>(
shared);
209 DataCollectorImpulseTpl<Scalar>* d2 =
dynamic_cast<DataCollectorImpulseTpl<Scalar>*
>(
shared);
210 if (d1 == NULL && d2 == NULL) {
212 "Invalid argument: the shared data should be derived from DataCollectorContact or DataCollectorImpulse");
219 const pinocchio::FrameIndex
id = model->get_id();
220 const boost::shared_ptr<StateMultibody>& state = boost::static_pointer_cast<StateMultibody>(model->get_state());
221 std::string frame_name = state->get_pinocchio()->frames[id].name;
222 bool found_contact =
false;
224 for (
typename ContactModelMultiple::ContactDataContainer::iterator it = d1->contacts->contacts.begin();
225 it != d1->contacts->contacts.end(); ++it) {
226 if (it->second->frame ==
id) {
227 ContactData1DTpl<Scalar>* d1d =
dynamic_cast<ContactData1DTpl<Scalar>*
>(it->second.get());
230 found_contact =
true;
234 ContactData3DTpl<Scalar>* d3d =
dynamic_cast<ContactData3DTpl<Scalar>*
>(it->second.get());
237 found_contact =
true;
241 ContactData6DTpl<Scalar>* d6d =
dynamic_cast<ContactData6DTpl<Scalar>*
>(it->second.get());
244 found_contact =
true;
248 throw_pretty(
"Domain error: there isn't defined at least a 3d contact for " + frame_name);
253 for (
typename ImpulseModelMultiple::ImpulseDataContainer::iterator it = d2->impulses->impulses.begin();
254 it != d2->impulses->impulses.end(); ++it) {
255 if (it->second->frame ==
id) {
256 ImpulseData3DTpl<Scalar>* d3d =
dynamic_cast<ImpulseData3DTpl<Scalar>*
>(it->second.get());
259 found_contact =
true;
263 ImpulseData6DTpl<Scalar>* d6d =
dynamic_cast<ImpulseData6DTpl<Scalar>*
>(it->second.get());
266 found_contact =
true;
270 throw_pretty(
"Domain error: there isn't defined at least a 3d impulse for " + frame_name);
275 if (!found_contact) {
276 throw_pretty(
"Domain error: there isn't defined contact/impulse data for " + frame_name);
280 boost::shared_ptr<ForceDataAbstractTpl<Scalar> >
contact;
293 #include "crocoddyl/multibody/residuals/contact-force.hxx" 295 #endif // CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_FORCE_HPP_
std::size_t nr_
Residual vector dimension.
std::size_t nu_
Control dimension.
MatrixXs Rx
Jacobian of the residual vector with respect the state.
MatrixXs Ru
Jacobian of the residual vector with respect the control.
boost::shared_ptr< StateAbstract > state_
State description.
VectorXs unone_
No control vector.
VectorXs r
Residual vector.
DataCollectorAbstract * shared
Shared data allocated by the action model.