9 #ifndef SOBEC_CONTACT_FWDDYN_HPP_ 10 #define SOBEC_CONTACT_FWDDYN_HPP_ 14 #include "crocoddyl/core/actuation-base.hpp" 15 #include "crocoddyl/core/costs/cost-sum.hpp" 16 #include "crocoddyl/core/diff-action-base.hpp" 17 #include "crocoddyl/multibody/contacts/multiple-contacts.hpp" 18 #include "crocoddyl/multibody/fwd.hpp" 19 #include "crocoddyl/multibody/states/multibody.hpp" 21 #include "crocoddyl/multibody/actions/contact-fwddyn.hpp" 26 namespace newcontacts {
84 template <
typename _Scalar>
86 :
public crocoddyl::DifferentialActionModelContactFwdDynamicsTpl<_Scalar> {
88 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
91 typedef crocoddyl::DifferentialActionModelContactFwdDynamicsTpl<Scalar>
Base;
92 typedef crocoddyl::DifferentialActionDataContactFwdDynamicsTpl<Scalar>
Data;
93 typedef crocoddyl::MathBaseTpl<Scalar>
MathBase;
98 typedef crocoddyl::DifferentialActionDataAbstractTpl<Scalar>
120 boost::shared_ptr<StateMultibody> state,
121 boost::shared_ptr<ActuationModelAbstract> actuation,
122 boost::shared_ptr<crocoContactModelMultiple> contacts,
123 boost::shared_ptr<CostModelSum> costs,
125 const bool enable_force =
false);
136 const boost::shared_ptr<DifferentialActionDataAbstract>& data,
137 const Eigen::Ref<const VectorXs>&
x,
const Eigen::Ref<const VectorXs>& u);
151 boost::shared_ptr<ContactModelMultipleTpl<Scalar>> sobec_contacts_;
162 #endif // SOBEC_CONTACT_FWDDYN_HPP_
Definition: activation-quad-ref.hpp:19