GCC Code Coverage Report


Directory: ./
File: include/crocoddyl/multibody/residuals/centroidal-momentum.hxx
Date: 2025-01-16 08:47:40
Exec Total Coverage
Lines: 32 33 97.0%
Branches: 23 46 50.0%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // BSD 3-Clause License
3 //
4 // Copyright (C) 2021, LAAS-CNRS, University of Edinburgh
5 // Copyright note valid unless otherwise stated in individual files.
6 // All rights reserved.
7 ///////////////////////////////////////////////////////////////////////////////
8
9 #include <pinocchio/algorithm/centroidal-derivatives.hpp>
10
11 #include "crocoddyl/core/utils/exception.hpp"
12 #include "crocoddyl/multibody/residuals/centroidal-momentum.hpp"
13
14 namespace crocoddyl {
15
16 template <typename Scalar>
17 54 ResidualModelCentroidalMomentumTpl<Scalar>::ResidualModelCentroidalMomentumTpl(
18 boost::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
2/4
✓ Branch 2 taken 54 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 54 times.
✗ Branch 7 not taken.
54 pin_model_(state->get_pinocchio()) {}
23
24 template <typename Scalar>
25 2 ResidualModelCentroidalMomentumTpl<Scalar>::ResidualModelCentroidalMomentumTpl(
26 boost::shared_ptr<StateMultibody> state, const Vector6s& href)
27 : Base(state, 6, true, true, false),
28 2 href_(href),
29
2/4
✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 2 times.
✗ Branch 7 not taken.
2 pin_model_(state->get_pinocchio()) {}
30
31 template <typename Scalar>
32 116 ResidualModelCentroidalMomentumTpl<
33 116 Scalar>::~ResidualModelCentroidalMomentumTpl() {}
34
35 template <typename Scalar>
36 2070 void ResidualModelCentroidalMomentumTpl<Scalar>::calc(
37 const boost::shared_ptr<ResidualDataAbstract>& data,
38 const Eigen::Ref<const VectorXs>&, const Eigen::Ref<const VectorXs>&) {
39 // Compute the residual residual give the reference centroidal momentum
40 2070 Data* d = static_cast<Data*>(data.get());
41
1/2
✓ Branch 4 taken 2070 times.
✗ Branch 5 not taken.
2070 data->r = d->pinocchio->hg.toVector() - href_;
42 2070 }
43
44 template <typename Scalar>
45 36 void ResidualModelCentroidalMomentumTpl<Scalar>::calcDiff(
46 const boost::shared_ptr<ResidualDataAbstract>& data,
47 const Eigen::Ref<const VectorXs>&, const Eigen::Ref<const VectorXs>&) {
48 36 Data* d = static_cast<Data*>(data.get());
49 36 const std::size_t& nv = state_->get_nv();
50
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));
51
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));
52
1/2
✓ Branch 1 taken 36 times.
✗ Branch 2 not taken.
36 pinocchio::getCentroidalDynamicsDerivatives(*pin_model_.get(), *d->pinocchio,
53 36 Rq, d->dhd_dq, d->dhd_dv, Rv);
54 36 }
55
56 template <typename Scalar>
57 boost::shared_ptr<ResidualDataAbstractTpl<Scalar> >
58 2404 ResidualModelCentroidalMomentumTpl<Scalar>::createData(
59 DataCollectorAbstract* const data) {
60 return boost::allocate_shared<Data>(Eigen::aligned_allocator<Data>(), this,
61
1/2
✓ Branch 2 taken 2404 times.
✗ Branch 3 not taken.
2404 data);
62 }
63
64 template <typename Scalar>
65 18 void ResidualModelCentroidalMomentumTpl<Scalar>::print(std::ostream& os) const {
66
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", "", "", "[",
67 "]");
68
1/2
✓ Branch 1 taken 18 times.
✗ Branch 2 not taken.
18 os << "ResidualModelCentroidalMomentum {href="
69
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) << "}";
70 18 }
71
72 template <typename Scalar>
73 const typename MathBaseTpl<Scalar>::Vector6s&
74 1 ResidualModelCentroidalMomentumTpl<Scalar>::get_reference() const {
75 1 return href_;
76 }
77
78 template <typename Scalar>
79 1 void ResidualModelCentroidalMomentumTpl<Scalar>::set_reference(
80 const Vector6s& href) {
81 1 href_ = href;
82 1 }
83
84 } // namespace crocoddyl
85