| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | /////////////////////////////////////////////////////////////////////////////// | ||
| 2 | // BSD 3-Clause License | ||
| 3 | // | ||
| 4 | // Copyright (C) 2019-2025, LAAS-CNRS, University of Edinburgh, CTU, INRIA, | ||
| 5 | // University of Oxford, Heriot-Watt University | ||
| 6 | // Copyright note valid unless otherwise stated in individual files. | ||
| 7 | // All rights reserved. | ||
| 8 | /////////////////////////////////////////////////////////////////////////////// | ||
| 9 | |||
| 10 | #ifndef CROCODDYL_MULTIBODY_ACTIONS_CONTACT_FWDDYN_HPP_ | ||
| 11 | #define CROCODDYL_MULTIBODY_ACTIONS_CONTACT_FWDDYN_HPP_ | ||
| 12 | |||
| 13 | #include "crocoddyl/core/actuation-base.hpp" | ||
| 14 | #include "crocoddyl/core/constraints/constraint-manager.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/data/contacts.hpp" | ||
| 19 | #include "crocoddyl/multibody/fwd.hpp" | ||
| 20 | #include "crocoddyl/multibody/states/multibody.hpp" | ||
| 21 | |||
| 22 | namespace crocoddyl { | ||
| 23 | |||
| 24 | /** | ||
| 25 | * @brief Differential action model for contact forward dynamics in multibody | ||
| 26 | * systems. | ||
| 27 | * | ||
| 28 | * This class implements contact forward dynamics given a stack of | ||
| 29 | * rigid-contacts described in `ContactModelMultipleTpl`, i.e., \f[ | ||
| 30 | * \left[\begin{matrix}\dot{\mathbf{v}} | ||
| 31 | * \\ -\boldsymbol{\lambda}\end{matrix}\right] = \left[\begin{matrix}\mathbf{M} | ||
| 32 | * & \mathbf{J}^{\top}_c \\ {\mathbf{J}_{c}} & \mathbf{0} | ||
| 33 | * \end{matrix}\right]^{-1} \left[\begin{matrix}\boldsymbol{\tau}_b | ||
| 34 | * \\ -\mathbf{a}_0 \\\end{matrix}\right], \f] where \f$\mathbf{q}\in Q\f$, | ||
| 35 | * \f$\mathbf{v}\in\mathbb{R}^{nv}\f$ are the configuration point and | ||
| 36 | * generalized velocity (its tangent vector), respectively; | ||
| 37 | * \f$\boldsymbol{\tau}_b=\boldsymbol{\tau} - | ||
| 38 | * \mathbf{h}(\mathbf{q},\mathbf{v})\f$ is the bias forces that depends on the | ||
| 39 | * torque inputs \f$\boldsymbol{\tau}\f$ and the Coriolis effect and gravity | ||
| 40 | * field \f$\mathbf{h}(\mathbf{q},\mathbf{v})\f$; | ||
| 41 | * \f$\mathbf{J}_c\in\mathbb{R}^{nc\times nv}\f$ is the contact Jacobian | ||
| 42 | * expressed in the local frame; and \f$\mathbf{a}_0\in\mathbb{R}^{nc}\f$ is the | ||
| 43 | * desired acceleration in the constraint space. To improve stability in the | ||
| 44 | * numerical integration, we define PD gains that are similar in spirit to | ||
| 45 | * Baumgarte stabilization: \f[ \mathbf{a}_0 = \mathbf{a}_{\lambda(c)} - \alpha | ||
| 46 | * \,^oM^{ref}_{\lambda(c)}\ominus\,^oM_{\lambda(c)} | ||
| 47 | * - \beta\mathbf{v}_{\lambda(c)}, \f] where \f$\mathbf{v}_{\lambda(c)}\f$, | ||
| 48 | * \f$\mathbf{a}_{\lambda(c)}\f$ are the spatial velocity and acceleration at | ||
| 49 | * the parent body of the contact \f$\lambda(c)\f$, respectively; \f$\alpha\f$ | ||
| 50 | * and \f$\beta\f$ are the stabilization gains; | ||
| 51 | * \f$\,^oM^{ref}_{\lambda(c)}\ominus\,^oM_{\lambda(c)}\f$ is the | ||
| 52 | * \f$\mathbb{SE}(3)\f$ inverse composition between the reference contact | ||
| 53 | * placement and the current one. | ||
| 54 | * | ||
| 55 | * The derivatives of the system acceleration and contact forces are computed | ||
| 56 | * efficiently based on the analytical derivatives of Recursive Newton Euler | ||
| 57 | * Algorithm (RNEA) as described in \cite mastalli-icra20. Note that the | ||
| 58 | * algorithm for computing the RNEA derivatives is described in \cite | ||
| 59 | * carpentier-rss18. | ||
| 60 | * | ||
| 61 | * The stack of cost and constraint functions are implemented in | ||
| 62 | * `CostModelSumTpl` and `ConstraintModelAbstractTpl`, respectively. The | ||
| 63 | * computation of the contact dynamics and its derivatives are carrying out | ||
| 64 | * inside `calc()` and `calcDiff()` functions, respectively. It is also | ||
| 65 | * important to remark that `calcDiff()` computes the derivatives using the | ||
| 66 | * latest stored values by `calc()`. Thus, we need to run `calc()` first. | ||
| 67 | * | ||
| 68 | * \sa `DifferentialActionModelAbstractTpl`, `calc()`, `calcDiff()`, | ||
| 69 | * `createData()` | ||
| 70 | */ | ||
| 71 | template <typename _Scalar> | ||
| 72 | class DifferentialActionModelContactFwdDynamicsTpl | ||
| 73 | : public DifferentialActionModelAbstractTpl<_Scalar> { | ||
| 74 | public: | ||
| 75 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW | ||
| 76 | ✗ | CROCODDYL_DERIVED_CAST(DifferentialActionModelBase, | |
| 77 | DifferentialActionModelContactFwdDynamicsTpl) | ||
| 78 | |||
| 79 | typedef _Scalar Scalar; | ||
| 80 | typedef DifferentialActionModelAbstractTpl<Scalar> Base; | ||
| 81 | typedef DifferentialActionDataContactFwdDynamicsTpl<Scalar> Data; | ||
| 82 | typedef MathBaseTpl<Scalar> MathBase; | ||
| 83 | typedef StateMultibodyTpl<Scalar> StateMultibody; | ||
| 84 | typedef CostModelSumTpl<Scalar> CostModelSum; | ||
| 85 | typedef ConstraintModelManagerTpl<Scalar> ConstraintModelManager; | ||
| 86 | typedef ContactModelMultipleTpl<Scalar> ContactModelMultiple; | ||
| 87 | typedef ActuationModelAbstractTpl<Scalar> ActuationModelAbstract; | ||
| 88 | typedef DifferentialActionDataAbstractTpl<Scalar> | ||
| 89 | DifferentialActionDataAbstract; | ||
| 90 | typedef typename MathBase::VectorXs VectorXs; | ||
| 91 | typedef typename MathBase::MatrixXs MatrixXs; | ||
| 92 | |||
| 93 | /** | ||
| 94 | * @brief Initialize the contact forward-dynamics action model | ||
| 95 | * | ||
| 96 | * It describes the dynamics evolution of a multibody system under | ||
| 97 | * rigid-contact constraints defined by `ContactModelMultipleTpl`. It computes | ||
| 98 | * the cost described in `CostModelSumTpl`. | ||
| 99 | * | ||
| 100 | * @param[in] state State of the multibody system | ||
| 101 | * @param[in] actuation Actuation model | ||
| 102 | * @param[in] contacts Stack of rigid contact | ||
| 103 | * @param[in] costs Stack of cost functions | ||
| 104 | * @param[in] JMinvJt_damping Damping term used in operational space inertia | ||
| 105 | * matrix (default 0.) | ||
| 106 | * @param[in] enable_force Enable the computation of the contact force | ||
| 107 | * derivatives (default false) | ||
| 108 | */ | ||
| 109 | DifferentialActionModelContactFwdDynamicsTpl( | ||
| 110 | std::shared_ptr<StateMultibody> state, | ||
| 111 | std::shared_ptr<ActuationModelAbstract> actuation, | ||
| 112 | std::shared_ptr<ContactModelMultiple> contacts, | ||
| 113 | std::shared_ptr<CostModelSum> costs, | ||
| 114 | const Scalar JMinvJt_damping = Scalar(0.), | ||
| 115 | const bool enable_force = false); | ||
| 116 | |||
| 117 | /** | ||
| 118 | * @brief Initialize the contact forward-dynamics action model | ||
| 119 | * | ||
| 120 | * It describes the dynamics evolution of a multibody system under | ||
| 121 | * rigid-contact constraints defined by `ContactModelMultipleTpl`. It computes | ||
| 122 | * the cost described in `CostModelSumTpl`. | ||
| 123 | * | ||
| 124 | * @param[in] state State of the multibody system | ||
| 125 | * @param[in] actuation Actuation model | ||
| 126 | * @param[in] contacts Stack of rigid contact | ||
| 127 | * @param[in] costs Stack of cost functions | ||
| 128 | * @param[in] constraints Stack of constraints | ||
| 129 | * @param[in] JMinvJt_damping Damping term used in operational space inertia | ||
| 130 | * matrix (default 0.) | ||
| 131 | * @param[in] enable_force Enable the computation of the contact force | ||
| 132 | * derivatives (default false) | ||
| 133 | */ | ||
| 134 | DifferentialActionModelContactFwdDynamicsTpl( | ||
| 135 | std::shared_ptr<StateMultibody> state, | ||
| 136 | std::shared_ptr<ActuationModelAbstract> actuation, | ||
| 137 | std::shared_ptr<ContactModelMultiple> contacts, | ||
| 138 | std::shared_ptr<CostModelSum> costs, | ||
| 139 | std::shared_ptr<ConstraintModelManager> constraints, | ||
| 140 | const Scalar JMinvJt_damping = Scalar(0.), | ||
| 141 | const bool enable_force = false); | ||
| 142 | ✗ | virtual ~DifferentialActionModelContactFwdDynamicsTpl() = default; | |
| 143 | |||
| 144 | /** | ||
| 145 | * @brief Compute the system acceleration, and cost value | ||
| 146 | * | ||
| 147 | * It computes the system acceleration using the contact dynamics. | ||
| 148 | * | ||
| 149 | * @param[in] data Contact forward-dynamics data | ||
| 150 | * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$ | ||
| 151 | * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$ | ||
| 152 | */ | ||
| 153 | virtual void calc(const std::shared_ptr<DifferentialActionDataAbstract>& data, | ||
| 154 | const Eigen::Ref<const VectorXs>& x, | ||
| 155 | const Eigen::Ref<const VectorXs>& u) override; | ||
| 156 | |||
| 157 | /** | ||
| 158 | * @brief Compute the total cost value for nodes that depends only on the | ||
| 159 | * state | ||
| 160 | * | ||
| 161 | * It updates the total cost and the system acceleration is not updated as it | ||
| 162 | * is expected to be zero. Additionally, it does not update the contact | ||
| 163 | * forces. This function is used in the terminal nodes of an optimal control | ||
| 164 | * problem. | ||
| 165 | * | ||
| 166 | * @param[in] data Contact forward-dynamics data | ||
| 167 | * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$ | ||
| 168 | */ | ||
| 169 | virtual void calc(const std::shared_ptr<DifferentialActionDataAbstract>& data, | ||
| 170 | const Eigen::Ref<const VectorXs>& x) override; | ||
| 171 | |||
| 172 | /** | ||
| 173 | * @brief Compute the derivatives of the contact dynamics, and cost function | ||
| 174 | * | ||
| 175 | * @param[in] data Contact forward-dynamics data | ||
| 176 | * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$ | ||
| 177 | * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$ | ||
| 178 | */ | ||
| 179 | virtual void calcDiff( | ||
| 180 | const std::shared_ptr<DifferentialActionDataAbstract>& data, | ||
| 181 | const Eigen::Ref<const VectorXs>& x, | ||
| 182 | const Eigen::Ref<const VectorXs>& u) override; | ||
| 183 | |||
| 184 | /** | ||
| 185 | * @brief Compute the derivatives of the cost functions with respect to the | ||
| 186 | * state only | ||
| 187 | * | ||
| 188 | * It updates the derivatives of the cost function with respect to the state | ||
| 189 | * only. Additionally, it does not update the contact forces derivatives. This | ||
| 190 | * function is used in the terminal nodes of an optimal control problem. | ||
| 191 | * | ||
| 192 | * @param[in] data Contact forward-dynamics data | ||
| 193 | * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$ | ||
| 194 | */ | ||
| 195 | virtual void calcDiff( | ||
| 196 | const std::shared_ptr<DifferentialActionDataAbstract>& data, | ||
| 197 | const Eigen::Ref<const VectorXs>& x) override; | ||
| 198 | |||
| 199 | /** | ||
| 200 | * @brief Create the contact forward-dynamics data | ||
| 201 | * | ||
| 202 | * @return contact forward-dynamics data | ||
| 203 | */ | ||
| 204 | virtual std::shared_ptr<DifferentialActionDataAbstract> createData() override; | ||
| 205 | |||
| 206 | /** | ||
| 207 | * @brief Cast the contact-fwddyn model to a different scalar type. | ||
| 208 | * | ||
| 209 | * It is useful for operations requiring different precision or scalar types. | ||
| 210 | * | ||
| 211 | * @tparam NewScalar The new scalar type to cast to. | ||
| 212 | * @return DifferentialActionModelContactFwdDynamicsTpl<NewScalar> A | ||
| 213 | * differential-action model with the new scalar type. | ||
| 214 | */ | ||
| 215 | template <typename NewScalar> | ||
| 216 | DifferentialActionModelContactFwdDynamicsTpl<NewScalar> cast() const; | ||
| 217 | |||
| 218 | /** | ||
| 219 | * @brief Check that the given data belongs to the contact forward-dynamics | ||
| 220 | * data | ||
| 221 | */ | ||
| 222 | virtual bool checkData( | ||
| 223 | const std::shared_ptr<DifferentialActionDataAbstract>& data) override; | ||
| 224 | |||
| 225 | /** | ||
| 226 | * @brief @copydoc Base::quasiStatic() | ||
| 227 | */ | ||
| 228 | virtual void quasiStatic( | ||
| 229 | const std::shared_ptr<DifferentialActionDataAbstract>& data, | ||
| 230 | Eigen::Ref<VectorXs> u, const Eigen::Ref<const VectorXs>& x, | ||
| 231 | const std::size_t maxiter = 100, | ||
| 232 | const Scalar tol = Scalar(1e-9)) override; | ||
| 233 | |||
| 234 | /** | ||
| 235 | * @brief Return the number of inequality constraints | ||
| 236 | */ | ||
| 237 | virtual std::size_t get_ng() const override; | ||
| 238 | |||
| 239 | /** | ||
| 240 | * @brief Return the number of equality constraints | ||
| 241 | */ | ||
| 242 | virtual std::size_t get_nh() const override; | ||
| 243 | |||
| 244 | /** | ||
| 245 | * @brief Return the number of equality terminal constraints | ||
| 246 | */ | ||
| 247 | virtual std::size_t get_ng_T() const override; | ||
| 248 | |||
| 249 | /** | ||
| 250 | * @brief Return the number of equality terminal constraints | ||
| 251 | */ | ||
| 252 | virtual std::size_t get_nh_T() const override; | ||
| 253 | |||
| 254 | /** | ||
| 255 | * @brief Return the lower bound of the inequality constraints | ||
| 256 | */ | ||
| 257 | virtual const VectorXs& get_g_lb() const override; | ||
| 258 | |||
| 259 | /** | ||
| 260 | * @brief Return the upper bound of the inequality constraints | ||
| 261 | */ | ||
| 262 | virtual const VectorXs& get_g_ub() const override; | ||
| 263 | |||
| 264 | /** | ||
| 265 | * @brief Return the actuation model | ||
| 266 | */ | ||
| 267 | const std::shared_ptr<ActuationModelAbstract>& get_actuation() const; | ||
| 268 | |||
| 269 | /** | ||
| 270 | * @brief Return the contact model | ||
| 271 | */ | ||
| 272 | const std::shared_ptr<ContactModelMultiple>& get_contacts() const; | ||
| 273 | |||
| 274 | /** | ||
| 275 | * @brief Return the cost model | ||
| 276 | */ | ||
| 277 | const std::shared_ptr<CostModelSum>& get_costs() const; | ||
| 278 | |||
| 279 | /** | ||
| 280 | * @brief Return the constraint model manager | ||
| 281 | */ | ||
| 282 | const std::shared_ptr<ConstraintModelManager>& get_constraints() const; | ||
| 283 | |||
| 284 | /** | ||
| 285 | * @brief Return the Pinocchio model | ||
| 286 | */ | ||
| 287 | pinocchio::ModelTpl<Scalar>& get_pinocchio() const; | ||
| 288 | |||
| 289 | /** | ||
| 290 | * @brief Return the armature vector | ||
| 291 | */ | ||
| 292 | const VectorXs& get_armature() const; | ||
| 293 | |||
| 294 | /** | ||
| 295 | * @brief Return the damping factor used in operational space inertia matrix | ||
| 296 | */ | ||
| 297 | const Scalar get_damping_factor() const; | ||
| 298 | |||
| 299 | /** | ||
| 300 | * @brief Modify the armature vector | ||
| 301 | */ | ||
| 302 | void set_armature(const VectorXs& armature); | ||
| 303 | |||
| 304 | /** | ||
| 305 | * @brief Modify the damping factor used in operational space inertia matrix | ||
| 306 | */ | ||
| 307 | void set_damping_factor(const Scalar damping); | ||
| 308 | |||
| 309 | /** | ||
| 310 | * @brief Print relevant information of the contact forward-dynamics model | ||
| 311 | * | ||
| 312 | * @param[out] os Output stream object | ||
| 313 | */ | ||
| 314 | virtual void print(std::ostream& os) const override; | ||
| 315 | |||
| 316 | protected: | ||
| 317 | using Base::g_lb_; //!< Lower bound of the inequality constraints | ||
| 318 | using Base::g_ub_; //!< Upper bound of the inequality constraints | ||
| 319 | using Base::nu_; //!< Control dimension | ||
| 320 | using Base::state_; //!< Model of the state | ||
| 321 | |||
| 322 | private: | ||
| 323 | void init(); | ||
| 324 | std::shared_ptr<ActuationModelAbstract> actuation_; //!< Actuation model | ||
| 325 | std::shared_ptr<ContactModelMultiple> contacts_; //!< Contact model | ||
| 326 | std::shared_ptr<CostModelSum> costs_; //!< Cost model | ||
| 327 | std::shared_ptr<ConstraintModelManager> constraints_; //!< Constraint model | ||
| 328 | pinocchio::ModelTpl<Scalar>* pinocchio_; //!< Pinocchio model | ||
| 329 | bool with_armature_; //!< Indicate if we have defined an armature | ||
| 330 | VectorXs armature_; //!< Armature vector | ||
| 331 | Scalar JMinvJt_damping_; //!< Damping factor used in operational space | ||
| 332 | //!< inertia matrix | ||
| 333 | bool enable_force_; //!< Indicate if we have enabled the computation of the | ||
| 334 | //!< contact-forces derivatives | ||
| 335 | }; | ||
| 336 | |||
| 337 | template <typename _Scalar> | ||
| 338 | struct DifferentialActionDataContactFwdDynamicsTpl | ||
| 339 | : public DifferentialActionDataAbstractTpl<_Scalar> { | ||
| 340 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW | ||
| 341 | typedef _Scalar Scalar; | ||
| 342 | typedef MathBaseTpl<Scalar> MathBase; | ||
| 343 | typedef DifferentialActionDataAbstractTpl<Scalar> Base; | ||
| 344 | typedef JointDataAbstractTpl<Scalar> JointDataAbstract; | ||
| 345 | typedef DataCollectorJointActMultibodyInContactTpl<Scalar> | ||
| 346 | DataCollectorJointActMultibodyInContact; | ||
| 347 | typedef typename MathBase::VectorXs VectorXs; | ||
| 348 | typedef typename MathBase::MatrixXs MatrixXs; | ||
| 349 | |||
| 350 | template <template <typename Scalar> class Model> | ||
| 351 | ✗ | explicit DifferentialActionDataContactFwdDynamicsTpl( | |
| 352 | Model<Scalar>* const model) | ||
| 353 | : Base(model), | ||
| 354 | ✗ | pinocchio(pinocchio::DataTpl<Scalar>(model->get_pinocchio())), | |
| 355 | ✗ | multibody( | |
| 356 | ✗ | &pinocchio, model->get_actuation()->createData(), | |
| 357 | std::make_shared<JointDataAbstract>( | ||
| 358 | ✗ | model->get_state(), model->get_actuation(), model->get_nu()), | |
| 359 | ✗ | model->get_contacts()->createData(&pinocchio)), | |
| 360 | ✗ | costs(model->get_costs()->createData(&multibody)), | |
| 361 | ✗ | Kinv(model->get_state()->get_nv() + | |
| 362 | ✗ | model->get_contacts()->get_nc_total(), | |
| 363 | ✗ | model->get_state()->get_nv() + | |
| 364 | ✗ | model->get_contacts()->get_nc_total()), | |
| 365 | ✗ | df_dx(model->get_contacts()->get_nc_total(), | |
| 366 | ✗ | model->get_state()->get_ndx()), | |
| 367 | ✗ | df_du(model->get_contacts()->get_nc_total(), model->get_nu()), | |
| 368 | ✗ | tmp_xstatic(model->get_state()->get_nx()), | |
| 369 | ✗ | tmp_Jstatic(model->get_state()->get_nv(), | |
| 370 | ✗ | model->get_nu() + model->get_contacts()->get_nc_total()) { | |
| 371 | ✗ | multibody.joint->dtau_du.diagonal().setOnes(); | |
| 372 | ✗ | costs->shareMemory(this); | |
| 373 | ✗ | if (model->get_constraints() != nullptr) { | |
| 374 | ✗ | constraints = model->get_constraints()->createData(&multibody); | |
| 375 | ✗ | constraints->shareMemory(this); | |
| 376 | } | ||
| 377 | ✗ | Kinv.setZero(); | |
| 378 | ✗ | df_dx.setZero(); | |
| 379 | ✗ | df_du.setZero(); | |
| 380 | ✗ | tmp_xstatic.setZero(); | |
| 381 | ✗ | tmp_Jstatic.setZero(); | |
| 382 | ✗ | pinocchio.lambda_c.resize(model->get_contacts()->get_nc_total()); | |
| 383 | ✗ | pinocchio.lambda_c.setZero(); | |
| 384 | ✗ | } | |
| 385 | ✗ | virtual ~DifferentialActionDataContactFwdDynamicsTpl() = default; | |
| 386 | |||
| 387 | pinocchio::DataTpl<Scalar> pinocchio; | ||
| 388 | DataCollectorJointActMultibodyInContact multibody; | ||
| 389 | std::shared_ptr<CostDataSumTpl<Scalar> > costs; | ||
| 390 | std::shared_ptr<ConstraintDataManagerTpl<Scalar> > constraints; | ||
| 391 | MatrixXs Kinv; | ||
| 392 | MatrixXs df_dx; | ||
| 393 | MatrixXs df_du; | ||
| 394 | VectorXs tmp_xstatic; | ||
| 395 | MatrixXs tmp_Jstatic; | ||
| 396 | |||
| 397 | using Base::cost; | ||
| 398 | using Base::Fu; | ||
| 399 | using Base::Fx; | ||
| 400 | using Base::Lu; | ||
| 401 | using Base::Luu; | ||
| 402 | using Base::Lx; | ||
| 403 | using Base::Lxu; | ||
| 404 | using Base::Lxx; | ||
| 405 | using Base::r; | ||
| 406 | using Base::xout; | ||
| 407 | }; | ||
| 408 | |||
| 409 | } // namespace crocoddyl | ||
| 410 | |||
| 411 | /* --- Details -------------------------------------------------------------- */ | ||
| 412 | /* --- Details -------------------------------------------------------------- */ | ||
| 413 | /* --- Details -------------------------------------------------------------- */ | ||
| 414 | #include <crocoddyl/multibody/actions/contact-fwddyn.hxx> | ||
| 415 | |||
| 416 | CROCODDYL_DECLARE_EXTERN_TEMPLATE_CLASS( | ||
| 417 | crocoddyl::DifferentialActionModelContactFwdDynamicsTpl) | ||
| 418 | CROCODDYL_DECLARE_EXTERN_TEMPLATE_STRUCT( | ||
| 419 | crocoddyl::DifferentialActionDataContactFwdDynamicsTpl) | ||
| 420 | |||
| 421 | #endif // CROCODDYL_MULTIBODY_ACTIONS_CONTACT_FWDDYN_HPP_ | ||
| 422 |