| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | /////////////////////////////////////////////////////////////////////////////// | ||
| 2 | // BSD 3-Clause License | ||
| 3 | // | ||
| 4 | // Copyright (C) 2021-2025, LAAS-CNRS, University of Edinburgh, | ||
| 5 | // Heriot-Watt University | ||
| 6 | // Copyright note valid unless otherwise stated in individual files. | ||
| 7 | // All rights reserved. | ||
| 8 | /////////////////////////////////////////////////////////////////////////////// | ||
| 9 | |||
| 10 | namespace crocoddyl { | ||
| 11 | |||
| 12 | template <typename Scalar> | ||
| 13 | ✗ | ResidualModelCentroidalMomentumTpl<Scalar>::ResidualModelCentroidalMomentumTpl( | |
| 14 | std::shared_ptr<StateMultibody> state, const Vector6s& href, | ||
| 15 | const std::size_t nu) | ||
| 16 | : Base(state, 6, nu, true, true, false), | ||
| 17 | ✗ | href_(href), | |
| 18 | ✗ | pin_model_(state->get_pinocchio()) {} | |
| 19 | |||
| 20 | template <typename Scalar> | ||
| 21 | ✗ | ResidualModelCentroidalMomentumTpl<Scalar>::ResidualModelCentroidalMomentumTpl( | |
| 22 | std::shared_ptr<StateMultibody> state, const Vector6s& href) | ||
| 23 | : Base(state, 6, true, true, false), | ||
| 24 | ✗ | href_(href), | |
| 25 | ✗ | pin_model_(state->get_pinocchio()) {} | |
| 26 | |||
| 27 | template <typename Scalar> | ||
| 28 | ✗ | void ResidualModelCentroidalMomentumTpl<Scalar>::calc( | |
| 29 | const std::shared_ptr<ResidualDataAbstract>& data, | ||
| 30 | const Eigen::Ref<const VectorXs>&, const Eigen::Ref<const VectorXs>&) { | ||
| 31 | // Compute the residual residual give the reference centroidal momentum | ||
| 32 | ✗ | Data* d = static_cast<Data*>(data.get()); | |
| 33 | ✗ | data->r = d->pinocchio->hg.toVector() - href_; | |
| 34 | ✗ | } | |
| 35 | |||
| 36 | template <typename Scalar> | ||
| 37 | ✗ | void ResidualModelCentroidalMomentumTpl<Scalar>::calcDiff( | |
| 38 | const std::shared_ptr<ResidualDataAbstract>& data, | ||
| 39 | const Eigen::Ref<const VectorXs>&, const Eigen::Ref<const VectorXs>&) { | ||
| 40 | ✗ | Data* d = static_cast<Data*>(data.get()); | |
| 41 | ✗ | const std::size_t& nv = state_->get_nv(); | |
| 42 | ✗ | Eigen::Ref<Matrix6xs> Rq(data->Rx.leftCols(nv)); | |
| 43 | ✗ | Eigen::Ref<Matrix6xs> Rv(data->Rx.rightCols(nv)); | |
| 44 | ✗ | pinocchio::getCentroidalDynamicsDerivatives(*pin_model_.get(), *d->pinocchio, | |
| 45 | ✗ | Rq, d->dhd_dq, d->dhd_dv, Rv); | |
| 46 | ✗ | } | |
| 47 | |||
| 48 | template <typename Scalar> | ||
| 49 | std::shared_ptr<ResidualDataAbstractTpl<Scalar> > | ||
| 50 | ✗ | ResidualModelCentroidalMomentumTpl<Scalar>::createData( | |
| 51 | DataCollectorAbstract* const data) { | ||
| 52 | ✗ | return std::allocate_shared<Data>(Eigen::aligned_allocator<Data>(), this, | |
| 53 | ✗ | data); | |
| 54 | } | ||
| 55 | |||
| 56 | template <typename Scalar> | ||
| 57 | template <typename NewScalar> | ||
| 58 | ResidualModelCentroidalMomentumTpl<NewScalar> | ||
| 59 | ✗ | ResidualModelCentroidalMomentumTpl<Scalar>::cast() const { | |
| 60 | typedef ResidualModelCentroidalMomentumTpl<NewScalar> ReturnType; | ||
| 61 | typedef StateMultibodyTpl<NewScalar> StateType; | ||
| 62 | ✗ | ReturnType ret( | |
| 63 | ✗ | std::static_pointer_cast<StateType>(state_->template cast<NewScalar>()), | |
| 64 | ✗ | href_.template cast<NewScalar>(), nu_); | |
| 65 | ✗ | return ret; | |
| 66 | } | ||
| 67 | |||
| 68 | template <typename Scalar> | ||
| 69 | ✗ | void ResidualModelCentroidalMomentumTpl<Scalar>::print(std::ostream& os) const { | |
| 70 | ✗ | const Eigen::IOFormat fmt(2, Eigen::DontAlignCols, ", ", ";\n", "", "", "[", | |
| 71 | "]"); | ||
| 72 | ✗ | os << "ResidualModelCentroidalMomentum {href=" | |
| 73 | ✗ | << href_.transpose().format(fmt) << "}"; | |
| 74 | ✗ | } | |
| 75 | |||
| 76 | template <typename Scalar> | ||
| 77 | const typename MathBaseTpl<Scalar>::Vector6s& | ||
| 78 | ✗ | ResidualModelCentroidalMomentumTpl<Scalar>::get_reference() const { | |
| 79 | ✗ | return href_; | |
| 80 | } | ||
| 81 | |||
| 82 | template <typename Scalar> | ||
| 83 | ✗ | void ResidualModelCentroidalMomentumTpl<Scalar>::set_reference( | |
| 84 | const Vector6s& href) { | ||
| 85 | ✗ | href_ = href; | |
| 86 | ✗ | } | |
| 87 | |||
| 88 | } // namespace crocoddyl | ||
| 89 |