GCC Code Coverage Report


Directory: ./
File: include/crocoddyl/multibody/residuals/com-position.hxx
Date: 2025-02-24 23:41:29
Exec Total Coverage
Lines: 26 27 96.3%
Branches: 19 38 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 "crocoddyl/core/utils/exception.hpp"
10 #include "crocoddyl/multibody/residuals/com-position.hpp"
11
12 namespace crocoddyl {
13
14 template <typename Scalar>
15 346 ResidualModelCoMPositionTpl<Scalar>::ResidualModelCoMPositionTpl(
16 std::shared_ptr<StateMultibody> state, const Vector3s& cref,
17 const std::size_t nu)
18
2/4
✓ Branch 2 taken 346 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 346 times.
✗ Branch 7 not taken.
346 : Base(state, 3, nu, true, false, false), cref_(cref) {}
19
20 template <typename Scalar>
21 4 ResidualModelCoMPositionTpl<Scalar>::ResidualModelCoMPositionTpl(
22 std::shared_ptr<StateMultibody> state, const Vector3s& cref)
23
2/4
✓ Branch 2 taken 4 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 4 times.
✗ Branch 7 not taken.
4 : Base(state, 3, true, false, false), cref_(cref) {}
24
25 template <typename Scalar>
26 704 ResidualModelCoMPositionTpl<Scalar>::~ResidualModelCoMPositionTpl() {}
27
28 template <typename Scalar>
29 8203 void ResidualModelCoMPositionTpl<Scalar>::calc(
30 const std::shared_ptr<ResidualDataAbstract>& data,
31 const Eigen::Ref<const VectorXs>&, const Eigen::Ref<const VectorXs>&) {
32 // Compute the residual residual give the reference CoMPosition position
33 8203 Data* d = static_cast<Data*>(data.get());
34
1/2
✓ Branch 4 taken 8203 times.
✗ Branch 5 not taken.
8203 data->r = d->pinocchio->com[0] - cref_;
35 8203 }
36
37 template <typename Scalar>
38 272 void ResidualModelCoMPositionTpl<Scalar>::calcDiff(
39 const std::shared_ptr<ResidualDataAbstract>& data,
40 const Eigen::Ref<const VectorXs>&, const Eigen::Ref<const VectorXs>&) {
41 272 Data* d = static_cast<Data*>(data.get());
42
43 // Compute the derivatives of the frame placement
44 272 const std::size_t nv = state_->get_nv();
45
1/2
✓ Branch 3 taken 272 times.
✗ Branch 4 not taken.
272 data->Rx.leftCols(nv) = d->pinocchio->Jcom;
46 272 }
47
48 template <typename Scalar>
49 std::shared_ptr<ResidualDataAbstractTpl<Scalar> >
50 9548 ResidualModelCoMPositionTpl<Scalar>::createData(
51 DataCollectorAbstract* const data) {
52 return std::allocate_shared<Data>(Eigen::aligned_allocator<Data>(), this,
53
1/2
✓ Branch 2 taken 9548 times.
✗ Branch 3 not taken.
9548 data);
54 }
55
56 template <typename Scalar>
57 63 void ResidualModelCoMPositionTpl<Scalar>::print(std::ostream& os) const {
58
7/14
✓ Branch 2 taken 63 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 63 times.
✗ Branch 7 not taken.
✓ Branch 10 taken 63 times.
✗ Branch 11 not taken.
✓ Branch 14 taken 63 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 63 times.
✗ Branch 19 not taken.
✓ Branch 22 taken 63 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 63 times.
✗ Branch 26 not taken.
126 const Eigen::IOFormat fmt(2, Eigen::DontAlignCols, ", ", ";\n", "", "", "[",
59 "]");
60
4/8
✓ Branch 1 taken 63 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 63 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 63 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 63 times.
✗ Branch 11 not taken.
126 os << "ResidualModelCoMPosition {cref=" << cref_.transpose().format(fmt)
61
1/2
✓ Branch 1 taken 63 times.
✗ Branch 2 not taken.
63 << "}";
62 63 }
63
64 template <typename Scalar>
65 const typename MathBaseTpl<Scalar>::Vector3s&
66 1 ResidualModelCoMPositionTpl<Scalar>::get_reference() const {
67 1 return cref_;
68 }
69
70 template <typename Scalar>
71 1 void ResidualModelCoMPositionTpl<Scalar>::set_reference(const Vector3s& cref) {
72 1 cref_ = cref;
73 1 }
74
75 } // namespace crocoddyl
76