| 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 | ✗ | ResidualModelCoMPositionTpl<Scalar>::ResidualModelCoMPositionTpl( | |
| 14 | std::shared_ptr<StateMultibody> state, const Vector3s& cref, | ||
| 15 | const std::size_t nu) | ||
| 16 | ✗ | : Base(state, 3, nu, true, false, false), cref_(cref) {} | |
| 17 | |||
| 18 | template <typename Scalar> | ||
| 19 | ✗ | ResidualModelCoMPositionTpl<Scalar>::ResidualModelCoMPositionTpl( | |
| 20 | std::shared_ptr<StateMultibody> state, const Vector3s& cref) | ||
| 21 | ✗ | : Base(state, 3, true, false, false), cref_(cref) {} | |
| 22 | |||
| 23 | template <typename Scalar> | ||
| 24 | ✗ | void ResidualModelCoMPositionTpl<Scalar>::calc( | |
| 25 | const std::shared_ptr<ResidualDataAbstract>& data, | ||
| 26 | const Eigen::Ref<const VectorXs>&, const Eigen::Ref<const VectorXs>&) { | ||
| 27 | // Compute the residual residual give the reference CoMPosition position | ||
| 28 | ✗ | Data* d = static_cast<Data*>(data.get()); | |
| 29 | ✗ | data->r = d->pinocchio->com[0] - cref_; | |
| 30 | ✗ | } | |
| 31 | |||
| 32 | template <typename Scalar> | ||
| 33 | ✗ | void ResidualModelCoMPositionTpl<Scalar>::calcDiff( | |
| 34 | const std::shared_ptr<ResidualDataAbstract>& data, | ||
| 35 | const Eigen::Ref<const VectorXs>&, const Eigen::Ref<const VectorXs>&) { | ||
| 36 | ✗ | Data* d = static_cast<Data*>(data.get()); | |
| 37 | |||
| 38 | // Compute the derivatives of the frame placement | ||
| 39 | ✗ | const std::size_t nv = state_->get_nv(); | |
| 40 | ✗ | data->Rx.leftCols(nv) = d->pinocchio->Jcom; | |
| 41 | ✗ | } | |
| 42 | |||
| 43 | template <typename Scalar> | ||
| 44 | std::shared_ptr<ResidualDataAbstractTpl<Scalar> > | ||
| 45 | ✗ | ResidualModelCoMPositionTpl<Scalar>::createData( | |
| 46 | DataCollectorAbstract* const data) { | ||
| 47 | ✗ | return std::allocate_shared<Data>(Eigen::aligned_allocator<Data>(), this, | |
| 48 | ✗ | data); | |
| 49 | } | ||
| 50 | |||
| 51 | template <typename Scalar> | ||
| 52 | template <typename NewScalar> | ||
| 53 | ResidualModelCoMPositionTpl<NewScalar> | ||
| 54 | ✗ | ResidualModelCoMPositionTpl<Scalar>::cast() const { | |
| 55 | typedef ResidualModelCoMPositionTpl<NewScalar> ReturnType; | ||
| 56 | typedef StateMultibodyTpl<NewScalar> StateType; | ||
| 57 | ✗ | ReturnType ret( | |
| 58 | ✗ | std::static_pointer_cast<StateType>(state_->template cast<NewScalar>()), | |
| 59 | ✗ | cref_.template cast<NewScalar>(), nu_); | |
| 60 | ✗ | return ret; | |
| 61 | } | ||
| 62 | |||
| 63 | template <typename Scalar> | ||
| 64 | ✗ | void ResidualModelCoMPositionTpl<Scalar>::print(std::ostream& os) const { | |
| 65 | ✗ | const Eigen::IOFormat fmt(2, Eigen::DontAlignCols, ", ", ";\n", "", "", "[", | |
| 66 | "]"); | ||
| 67 | ✗ | os << "ResidualModelCoMPosition {cref=" << cref_.transpose().format(fmt) | |
| 68 | ✗ | << "}"; | |
| 69 | ✗ | } | |
| 70 | |||
| 71 | template <typename Scalar> | ||
| 72 | const typename MathBaseTpl<Scalar>::Vector3s& | ||
| 73 | ✗ | ResidualModelCoMPositionTpl<Scalar>::get_reference() const { | |
| 74 | ✗ | return cref_; | |
| 75 | } | ||
| 76 | |||
| 77 | template <typename Scalar> | ||
| 78 | ✗ | void ResidualModelCoMPositionTpl<Scalar>::set_reference(const Vector3s& cref) { | |
| 79 | ✗ | cref_ = cref; | |
| 80 | ✗ | } | |
| 81 | |||
| 82 | } // namespace crocoddyl | ||
| 83 |