9 #ifndef CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_WRENCH_CONE_HPP_ 10 #define CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_WRENCH_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/wrench-cone.hpp" 26 #include "crocoddyl/core/utils/exception.hpp" 49 template <
typename _Scalar>
50 class ResidualModelContactWrenchConeTpl :
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 ResidualDataContactWrenchConeTpl<Scalar> Data;
58 typedef StateMultibodyTpl<Scalar> StateMultibody;
59 typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract;
60 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
61 typedef WrenchConeTpl<Scalar> WrenchCone;
62 typedef typename MathBase::VectorXs VectorXs;
63 typedef typename MathBase::MatrixXs MatrixXs;
64 typedef typename MathBase::MatrixX6s MatrixX6s;
75 const WrenchCone& fref,
const std::size_t nu);
87 const WrenchCone& 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);
126 virtual void calcDiff(
const boost::shared_ptr<ResidualDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x,
127 const Eigen::Ref<const VectorXs>& u);
138 virtual void calcDiff(
const boost::shared_ptr<ResidualDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x);
146 virtual boost::shared_ptr<ResidualDataAbstract>
createData(DataCollectorAbstract*
const data);
151 pinocchio::FrameIndex
get_id()
const;
161 void set_id(
const pinocchio::FrameIndex
id);
173 virtual void print(std::ostream& os)
const;
181 pinocchio::FrameIndex id_;
185 template <
typename _Scalar>
186 struct ResidualDataContactWrenchConeTpl :
public ResidualDataAbstractTpl<_Scalar> {
187 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
189 typedef _Scalar Scalar;
190 typedef MathBaseTpl<Scalar> MathBase;
191 typedef ResidualDataAbstractTpl<Scalar> Base;
192 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
193 typedef ContactModelMultipleTpl<Scalar> ContactModelMultiple;
194 typedef ImpulseModelMultipleTpl<Scalar> ImpulseModelMultiple;
195 typedef StateMultibodyTpl<Scalar> StateMultibody;
196 typedef typename MathBase::MatrixXs MatrixXs;
198 template <
template <
typename Scalar>
class Model>
199 ResidualDataContactWrenchConeTpl(Model<Scalar>*
const model, DataCollectorAbstract*
const data) : Base(model, data) {
201 bool is_contact =
true;
202 DataCollectorContactTpl<Scalar>* d1 =
dynamic_cast<DataCollectorContactTpl<Scalar>*
>(
shared);
203 DataCollectorImpulseTpl<Scalar>* d2 =
dynamic_cast<DataCollectorImpulseTpl<Scalar>*
>(
shared);
204 if (d1 == NULL && d2 == NULL) {
206 "Invalid argument: the shared data should be derived from DataCollectorContact or DataCollectorImpulse");
213 const pinocchio::FrameIndex
id = model->get_id();
214 const boost::shared_ptr<StateMultibody>& state = boost::static_pointer_cast<StateMultibody>(model->get_state());
215 std::string frame_name = state->get_pinocchio()->frames[id].name;
216 bool found_contact =
false;
218 for (
typename ContactModelMultiple::ContactDataContainer::iterator it = d1->contacts->contacts.begin();
219 it != d1->contacts->contacts.end(); ++it) {
220 if (it->second->frame ==
id) {
221 ContactData3DTpl<Scalar>* d3d =
dynamic_cast<ContactData3DTpl<Scalar>*
>(it->second.get());
223 found_contact =
true;
225 throw_pretty(
"Domain error: there isn't defined at least a 6d contact for " + frame_name);
228 ContactData6DTpl<Scalar>* d6d =
dynamic_cast<ContactData6DTpl<Scalar>*
>(it->second.get());
230 found_contact =
true;
234 throw_pretty(
"Domain error: there isn't defined at least a 6d contact for " + frame_name);
239 for (
typename ImpulseModelMultiple::ImpulseDataContainer::iterator it = d2->impulses->impulses.begin();
240 it != d2->impulses->impulses.end(); ++it) {
241 if (it->second->frame ==
id) {
242 ImpulseData3DTpl<Scalar>* d3d =
dynamic_cast<ImpulseData3DTpl<Scalar>*
>(it->second.get());
244 found_contact =
true;
246 throw_pretty(
"Domain error: there isn't defined at least a 6d contact for " + frame_name);
249 ImpulseData6DTpl<Scalar>* d6d =
dynamic_cast<ImpulseData6DTpl<Scalar>*
>(it->second.get());
251 found_contact =
true;
255 throw_pretty(
"Domain error: there isn't defined at least a 6d contact for " + frame_name);
260 if (!found_contact) {
261 throw_pretty(
"Domain error: there isn't defined contact data for " + frame_name);
265 boost::shared_ptr<ForceDataAbstractTpl<Scalar> >
contact;
277 #include "crocoddyl/multibody/residuals/contact-wrench-cone.hxx" 279 #endif // CROCODDYL_MULTIBODY_RESIDUALS_CONTACT_WRENCH_CONE_HPP_
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.