GCC Code Coverage Report


Directory: ./
File: include/crocoddyl/multibody/residuals/contact-force.hxx
Date: 2025-03-26 19:23:43
Exec Total Coverage
Lines: 59 94 62.8%
Branches: 31 138 22.5%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // BSD 3-Clause License
3 //
4 // Copyright (C) 2019-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 "crocoddyl/multibody/residuals/contact-force.hpp"
11
12 namespace crocoddyl {
13
14 template <typename Scalar>
15 1674 ResidualModelContactForceTpl<Scalar>::ResidualModelContactForceTpl(
16 std::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id,
17 const Force& fref, const std::size_t nc, const std::size_t nu,
18 const bool fwddyn)
19 : Base(state, nc, nu, fwddyn ? true : false, fwddyn ? true : false, true),
20 1674 fwddyn_(fwddyn),
21 1674 update_jacobians_(true),
22 1674 id_(id),
23
6/8
✓ Branch 0 taken 624 times.
✓ Branch 1 taken 1050 times.
✓ Branch 2 taken 624 times.
✓ Branch 3 taken 1050 times.
✓ Branch 6 taken 1674 times.
✗ Branch 7 not taken.
✓ Branch 10 taken 1674 times.
✗ Branch 11 not taken.
1674 fref_(fref) {
24
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 1674 times.
1674 if (nc > 6) {
25 throw_pretty(
26 "Invalid argument in ResidualModelContactForce: nc should be less than "
27 "6");
28 }
29
2/4
✓ Branch 2 taken 1674 times.
✗ Branch 3 not taken.
✗ Branch 5 not taken.
✓ Branch 6 taken 1674 times.
1674 if (static_cast<pinocchio::FrameIndex>(state->get_pinocchio()->nframes) <=
30 id) {
31 throw_pretty(
32 "Invalid argument: "
33 << "the frame index is wrong (it does not exist in the robot)");
34 }
35 1674 }
36
37 template <typename Scalar>
38 1 ResidualModelContactForceTpl<Scalar>::ResidualModelContactForceTpl(
39 std::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id,
40 const Force& fref, const std::size_t nc)
41 : Base(state, nc),
42 1 fwddyn_(true),
43 1 update_jacobians_(true),
44 1 id_(id),
45
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
1 fref_(fref) {
46
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 1 times.
1 if (nc > 6) {
47 throw_pretty(
48 "Invalid argument in ResidualModelContactForce: nc should be less than "
49 "6");
50 }
51
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✗ Branch 5 not taken.
✓ Branch 6 taken 1 times.
1 if (static_cast<pinocchio::FrameIndex>(state->get_pinocchio()->nframes) <=
52 id) {
53 throw_pretty(
54 "Invalid argument: "
55 << "the frame index is wrong (it does not exist in the robot)");
56 }
57 1 }
58
59 template <typename Scalar>
60 71770 void ResidualModelContactForceTpl<Scalar>::calc(
61 const std::shared_ptr<ResidualDataAbstract>& data,
62 const Eigen::Ref<const VectorXs>&, const Eigen::Ref<const VectorXs>&) {
63 71770 Data* d = static_cast<Data*>(data.get());
64
65 // We transform the force to the contact frame
66
2/4
✗ Branch 0 not taken.
✓ Branch 1 taken 40014 times.
✓ Branch 2 taken 31756 times.
✗ Branch 3 not taken.
71770 switch (d->contact_type) {
67 case Contact1D:
68 data->r = ((d->contact->f - fref_).linear()).row(2);
69 break;
70 40014 case Contact3D:
71
2/4
✓ Branch 3 taken 40014 times.
✗ Branch 4 not taken.
✓ Branch 7 taken 40014 times.
✗ Branch 8 not taken.
40014 data->r = (d->contact->f - fref_).linear();
72 40014 break;
73 31756 case Contact6D:
74
2/4
✓ Branch 3 taken 31756 times.
✗ Branch 4 not taken.
✓ Branch 7 taken 31756 times.
✗ Branch 8 not taken.
31756 data->r = (d->contact->f - fref_).toVector();
75 31756 break;
76 default:
77 break;
78 }
79 71770 }
80
81 template <typename Scalar>
82 15197 void ResidualModelContactForceTpl<Scalar>::calc(
83 const std::shared_ptr<ResidualDataAbstract>& data,
84 const Eigen::Ref<const VectorXs>&) {
85 15197 data->r.setZero();
86 15197 }
87
88 template <typename Scalar>
89 9412 void ResidualModelContactForceTpl<Scalar>::calcDiff(
90 const std::shared_ptr<ResidualDataAbstract>& data,
91 const Eigen::Ref<const VectorXs>&, const Eigen::Ref<const VectorXs>&) {
92
3/4
✓ Branch 0 taken 4389 times.
✓ Branch 1 taken 5023 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 4389 times.
9412 if (fwddyn_ || update_jacobians_) {
93 5023 updateJacobians(data);
94 }
95 9412 }
96
97 template <typename Scalar>
98 384 void ResidualModelContactForceTpl<Scalar>::calcDiff(
99 const std::shared_ptr<ResidualDataAbstract>& data,
100 const Eigen::Ref<const VectorXs>&) {
101 384 data->Rx.setZero();
102 384 }
103
104 template <typename Scalar>
105 std::shared_ptr<ResidualDataAbstractTpl<Scalar> >
106 161402 ResidualModelContactForceTpl<Scalar>::createData(
107 DataCollectorAbstract* const data) {
108
1/2
✓ Branch 1 taken 161402 times.
✗ Branch 2 not taken.
322804 std::shared_ptr<ResidualDataAbstract> d =
109 161402 std::allocate_shared<Data>(Eigen::aligned_allocator<Data>(), this, data);
110
2/2
✓ Branch 0 taken 114294 times.
✓ Branch 1 taken 47108 times.
161402 if (!fwddyn_) {
111
1/2
✓ Branch 1 taken 114294 times.
✗ Branch 2 not taken.
114294 updateJacobians(d);
112 }
113 161402 return d;
114 }
115
116 template <typename Scalar>
117 119317 void ResidualModelContactForceTpl<Scalar>::updateJacobians(
118 const std::shared_ptr<ResidualDataAbstract>& data) {
119 119317 Data* d = static_cast<Data*>(data.get());
120
121 119317 const MatrixXs& df_dx = d->contact->df_dx;
122 119317 const MatrixXs& df_du = d->contact->df_du;
123
2/4
✗ Branch 0 not taken.
✓ Branch 1 taken 74887 times.
✓ Branch 2 taken 44430 times.
✗ Branch 3 not taken.
119317 switch (d->contact_type) {
124 case Contact1D:
125 data->Rx = df_dx.template topRows<1>();
126 data->Ru = df_du.template topRows<1>();
127 break;
128 74887 case Contact3D:
129
1/2
✓ Branch 3 taken 74887 times.
✗ Branch 4 not taken.
74887 data->Rx = df_dx.template topRows<3>();
130
1/2
✓ Branch 3 taken 74887 times.
✗ Branch 4 not taken.
74887 data->Ru = df_du.template topRows<3>();
131 74887 break;
132 44430 case Contact6D:
133 44430 data->Rx = df_dx;
134 44430 data->Ru = df_du;
135 44430 break;
136 default:
137 break;
138 }
139 119317 update_jacobians_ = false;
140 119317 }
141
142 template <typename Scalar>
143 template <typename NewScalar>
144 ResidualModelContactForceTpl<NewScalar>
145 ResidualModelContactForceTpl<Scalar>::cast() const {
146 typedef ResidualModelContactForceTpl<NewScalar> ReturnType;
147 typedef StateMultibodyTpl<NewScalar> StateType;
148 ReturnType ret(
149 std::static_pointer_cast<StateType>(state_->template cast<NewScalar>()),
150 id_, fref_.template cast<NewScalar>(), nr_, nu_, fwddyn_);
151 return ret;
152 }
153
154 template <typename Scalar>
155 void ResidualModelContactForceTpl<Scalar>::print(std::ostream& os) const {
156 std::shared_ptr<StateMultibody> s =
157 std::static_pointer_cast<StateMultibody>(state_);
158 const Eigen::IOFormat fmt(2, Eigen::DontAlignCols, ", ", ";\n", "", "", "[",
159 "]");
160 os << "ResidualModelContactForce {frame="
161 << s->get_pinocchio()->frames[id_].name
162 << ", fref=" << fref_.toVector().head(nr_).transpose().format(fmt) << "}";
163 }
164
165 template <typename Scalar>
166 bool ResidualModelContactForceTpl<Scalar>::is_fwddyn() const {
167 return fwddyn_;
168 }
169
170 template <typename Scalar>
171 161402 pinocchio::FrameIndex ResidualModelContactForceTpl<Scalar>::get_id() const {
172 161402 return id_;
173 }
174
175 template <typename Scalar>
176 const pinocchio::ForceTpl<Scalar>&
177 ResidualModelContactForceTpl<Scalar>::get_reference() const {
178 return fref_;
179 }
180
181 template <typename Scalar>
182 void ResidualModelContactForceTpl<Scalar>::set_id(
183 const pinocchio::FrameIndex id) {
184 id_ = id;
185 }
186
187 template <typename Scalar>
188 void ResidualModelContactForceTpl<Scalar>::set_reference(
189 const Force& reference) {
190 fref_ = reference;
191 update_jacobians_ = true;
192 }
193
194 } // namespace crocoddyl
195