GCC Code Coverage Report


Directory: ./
File: include/crocoddyl/multibody/residuals/centroidal-momentum.hxx
Date: 2025-03-26 19:23:43
Exec Total Coverage
Lines: 30 36 83.3%
Branches: 26 58 44.8%

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 #include <pinocchio/algorithm/centroidal-derivatives.hpp>
11
12 #include "crocoddyl/multibody/residuals/centroidal-momentum.hpp"
13
14 namespace crocoddyl {
15
16 template <typename Scalar>
17 54 ResidualModelCentroidalMomentumTpl<Scalar>::ResidualModelCentroidalMomentumTpl(
18 std::shared_ptr<StateMultibody> state, const Vector6s& href,
19 const std::size_t nu)
20 : Base(state, 6, nu, true, true, false),
21 54 href_(href),
22
3/6
✓ Branch 2 taken 54 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 54 times.
✗ Branch 7 not taken.
✓ Branch 10 taken 54 times.
✗ Branch 11 not taken.
54 pin_model_(state->get_pinocchio()) {}
23
24 template <typename Scalar>
25 2 ResidualModelCentroidalMomentumTpl<Scalar>::ResidualModelCentroidalMomentumTpl(
26 std::shared_ptr<StateMultibody> state, const Vector6s& href)
27 : Base(state, 6, true, true, false),
28 2 href_(href),
29
3/6
✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 2 times.
✗ Branch 7 not taken.
✓ Branch 10 taken 2 times.
✗ Branch 11 not taken.
2 pin_model_(state->get_pinocchio()) {}
30
31 template <typename Scalar>
32 2070 void ResidualModelCentroidalMomentumTpl<Scalar>::calc(
33 const std::shared_ptr<ResidualDataAbstract>& data,
34 const Eigen::Ref<const VectorXs>&, const Eigen::Ref<const VectorXs>&) {
35 // Compute the residual residual give the reference centroidal momentum
36 2070 Data* d = static_cast<Data*>(data.get());
37
1/2
✓ Branch 4 taken 2070 times.
✗ Branch 5 not taken.
2070 data->r = d->pinocchio->hg.toVector() - href_;
38 2070 }
39
40 template <typename Scalar>
41 36 void ResidualModelCentroidalMomentumTpl<Scalar>::calcDiff(
42 const std::shared_ptr<ResidualDataAbstract>& data,
43 const Eigen::Ref<const VectorXs>&, const Eigen::Ref<const VectorXs>&) {
44 36 Data* d = static_cast<Data*>(data.get());
45
1/2
✓ Branch 2 taken 36 times.
✗ Branch 3 not taken.
36 const std::size_t& nv = state_->get_nv();
46
2/4
✓ Branch 2 taken 36 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 36 times.
✗ Branch 6 not taken.
36 Eigen::Ref<Matrix6xs> Rq(data->Rx.leftCols(nv));
47
2/4
✓ Branch 2 taken 36 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 36 times.
✗ Branch 6 not taken.
36 Eigen::Ref<Matrix6xs> Rv(data->Rx.rightCols(nv));
48
1/2
✓ Branch 1 taken 36 times.
✗ Branch 2 not taken.
36 pinocchio::getCentroidalDynamicsDerivatives(*pin_model_.get(), *d->pinocchio,
49 36 Rq, d->dhd_dq, d->dhd_dv, Rv);
50 36 }
51
52 template <typename Scalar>
53 std::shared_ptr<ResidualDataAbstractTpl<Scalar> >
54 2404 ResidualModelCentroidalMomentumTpl<Scalar>::createData(
55 DataCollectorAbstract* const data) {
56 return std::allocate_shared<Data>(Eigen::aligned_allocator<Data>(), this,
57
1/2
✓ Branch 2 taken 2404 times.
✗ Branch 3 not taken.
2404 data);
58 }
59
60 template <typename Scalar>
61 template <typename NewScalar>
62 ResidualModelCentroidalMomentumTpl<NewScalar>
63 ResidualModelCentroidalMomentumTpl<Scalar>::cast() const {
64 typedef ResidualModelCentroidalMomentumTpl<NewScalar> ReturnType;
65 typedef StateMultibodyTpl<NewScalar> StateType;
66 ReturnType ret(
67 std::static_pointer_cast<StateType>(state_->template cast<NewScalar>()),
68 href_.template cast<NewScalar>(), nu_);
69 return ret;
70 }
71
72 template <typename Scalar>
73 18 void ResidualModelCentroidalMomentumTpl<Scalar>::print(std::ostream& os) const {
74
7/14
✓ Branch 2 taken 18 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 18 times.
✗ Branch 7 not taken.
✓ Branch 10 taken 18 times.
✗ Branch 11 not taken.
✓ Branch 14 taken 18 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 18 times.
✗ Branch 19 not taken.
✓ Branch 22 taken 18 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 18 times.
✗ Branch 26 not taken.
36 const Eigen::IOFormat fmt(2, Eigen::DontAlignCols, ", ", ";\n", "", "", "[",
75 "]");
76
1/2
✓ Branch 1 taken 18 times.
✗ Branch 2 not taken.
18 os << "ResidualModelCentroidalMomentum {href="
77
4/8
✓ Branch 1 taken 18 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 18 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 18 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 18 times.
✗ Branch 11 not taken.
18 << href_.transpose().format(fmt) << "}";
78 18 }
79
80 template <typename Scalar>
81 const typename MathBaseTpl<Scalar>::Vector6s&
82 1 ResidualModelCentroidalMomentumTpl<Scalar>::get_reference() const {
83 1 return href_;
84 }
85
86 template <typename Scalar>
87 1 void ResidualModelCentroidalMomentumTpl<Scalar>::set_reference(
88 const Vector6s& href) {
89 1 href_ = href;
90 1 }
91
92 } // namespace crocoddyl
93