contact-fwddyn.hpp
Go to the documentation of this file.
1 // BSD 3-Clause License
3 //
4 // Copyright (C) 2019-2021, LAAS-CNRS, University of Edinburgh, CTU, INRIA,
5 // University of Oxford Copyright note valid unless otherwise stated in
6 // individual files. All rights reserved.
8 
9 #ifndef SOBEC_CONTACT_FWDDYN_HPP_
10 #define SOBEC_CONTACT_FWDDYN_HPP_
11 
12 #include <stdexcept>
13 
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"
20 // #include "crocoddyl/multibody/data/contacts.hpp"
21 #include "crocoddyl/multibody/actions/contact-fwddyn.hpp"
23 #include "sobec/fwd.hpp"
24 
25 namespace sobec {
26 namespace newcontacts {
27 
84 template <typename _Scalar>
86  : public crocoddyl::DifferentialActionModelContactFwdDynamicsTpl<_Scalar> {
87  public:
88  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
89 
90  typedef _Scalar Scalar;
91  typedef crocoddyl::DifferentialActionModelContactFwdDynamicsTpl<Scalar> Base;
92  typedef crocoddyl::DifferentialActionDataContactFwdDynamicsTpl<Scalar> Data;
93  typedef crocoddyl::MathBaseTpl<Scalar> MathBase;
94  typedef crocoddyl::CostModelSumTpl<Scalar> CostModelSum;
95  typedef crocoddyl::StateMultibodyTpl<Scalar> StateMultibody;
96  typedef crocoddyl::ContactModelMultipleTpl<Scalar> crocoContactModelMultiple;
97  typedef crocoddyl::ActuationModelAbstractTpl<Scalar> ActuationModelAbstract;
98  typedef crocoddyl::DifferentialActionDataAbstractTpl<Scalar>
100  typedef typename MathBase::VectorXs VectorXs;
101  typedef typename MathBase::MatrixXs MatrixXs;
102 
120  boost::shared_ptr<StateMultibody> state,
121  boost::shared_ptr<ActuationModelAbstract> actuation,
122  boost::shared_ptr<crocoContactModelMultiple> contacts,
123  boost::shared_ptr<CostModelSum> costs,
124  const Scalar JMinvJt_damping = Scalar(0.),
125  const bool enable_force = false);
127 
135  virtual void calcDiff(
136  const boost::shared_ptr<DifferentialActionDataAbstract>& data,
137  const Eigen::Ref<const VectorXs>& x, const Eigen::Ref<const VectorXs>& u);
138 
139  // /**
140  // * @brief @copydoc Base::quasiStatic()
141  // */
142  // virtual void quasiStatic(const
143  // boost::shared_ptr<DifferentialActionDataAbstract>& data,
144  // Eigen::Ref<VectorXs> u,
145  // const Eigen::Ref<const VectorXs>& x, const
146  // std::size_t maxiter = 100, const Scalar tol =
147  // Scalar(1e-9));
148 
149  private:
150  bool enable_force_;
151  boost::shared_ptr<ContactModelMultipleTpl<Scalar>> sobec_contacts_;
152 };
153 
154 } // namespace newcontacts
155 } // namespace sobec
156 
157 /* --- Details -------------------------------------------------------------- */
158 /* --- Details -------------------------------------------------------------- */
159 /* --- Details -------------------------------------------------------------- */
161 
162 #endif // SOBEC_CONTACT_FWDDYN_HPP_
sobec::newcontacts::DifferentialActionModelContactFwdDynamicsTpl::VectorXs
MathBase::VectorXs VectorXs
Definition: contact-fwddyn.hpp:100
sobec::newcontacts::DifferentialActionModelContactFwdDynamicsTpl::MathBase
crocoddyl::MathBaseTpl< Scalar > MathBase
Definition: contact-fwddyn.hpp:93
fwd.hpp
sobec::newcontacts::DifferentialActionModelContactFwdDynamicsTpl::ActuationModelAbstract
crocoddyl::ActuationModelAbstractTpl< Scalar > ActuationModelAbstract
Definition: contact-fwddyn.hpp:97
sobec::newcontacts::DifferentialActionModelContactFwdDynamicsTpl::DifferentialActionDataAbstract
crocoddyl::DifferentialActionDataAbstractTpl< Scalar > DifferentialActionDataAbstract
Definition: contact-fwddyn.hpp:99
sobec::newcontacts::DifferentialActionModelContactFwdDynamicsTpl
Differential action model for contact forward dynamics in multibody systems.
Definition: contact-fwddyn.hpp:85
sobec::newcontacts::DifferentialActionModelContactFwdDynamicsTpl::Scalar
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
Definition: contact-fwddyn.hpp:90
sobec
Definition: activation-quad-ref.hpp:19
sobec::newcontacts::DifferentialActionModelContactFwdDynamicsTpl::crocoContactModelMultiple
crocoddyl::ContactModelMultipleTpl< Scalar > crocoContactModelMultiple
Definition: contact-fwddyn.hpp:96
sobec::newcontacts::DifferentialActionModelContactFwdDynamicsTpl::calcDiff
virtual void calcDiff(const boost::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the derivatives of the contact dynamics, and cost function.
Definition: contact-fwddyn.hxx:43
sobec::newcontacts::DifferentialActionModelContactFwdDynamicsTpl::StateMultibody
crocoddyl::StateMultibodyTpl< Scalar > StateMultibody
Definition: contact-fwddyn.hpp:95
sobec::newcontacts::DifferentialActionModelContactFwdDynamicsTpl::CostModelSum
crocoddyl::CostModelSumTpl< Scalar > CostModelSum
Definition: contact-fwddyn.hpp:94
multiple-contacts.hpp
sobec::newcontacts::x
@ x
Definition: contact1d.hpp:26
sobec::newcontacts::DifferentialActionModelContactFwdDynamicsTpl::~DifferentialActionModelContactFwdDynamicsTpl
virtual ~DifferentialActionModelContactFwdDynamicsTpl()
Definition: contact-fwddyn.hxx:40
sobec::newcontacts::DifferentialActionModelContactFwdDynamicsTpl::Base
crocoddyl::DifferentialActionModelContactFwdDynamicsTpl< Scalar > Base
Definition: contact-fwddyn.hpp:91
sobec::newcontacts::DifferentialActionModelContactFwdDynamicsTpl::Data
crocoddyl::DifferentialActionDataContactFwdDynamicsTpl< Scalar > Data
Definition: contact-fwddyn.hpp:92
contact-fwddyn.hxx
sobec::newcontacts::DifferentialActionModelContactFwdDynamicsTpl::DifferentialActionModelContactFwdDynamicsTpl
DifferentialActionModelContactFwdDynamicsTpl(boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ActuationModelAbstract > actuation, boost::shared_ptr< crocoContactModelMultiple > contacts, boost::shared_ptr< CostModelSum > costs, const Scalar JMinvJt_damping=Scalar(0.), const bool enable_force=false)
Initialize the contact forward-dynamics action model.
Definition: contact-fwddyn.hxx:26
sobec::newcontacts::DifferentialActionModelContactFwdDynamicsTpl::MatrixXs
MathBase::MatrixXs MatrixXs
Definition: contact-fwddyn.hpp:101