GCC Code Coverage Report


Directory: ./
File: unittest/factory/action.cpp
Date: 2025-01-16 08:47:40
Exec Total Coverage
Lines: 184 193 95.3%
Branches: 163 325 50.2%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // BSD 3-Clause License
3 //
4 // Copyright (C) 2019-2024, University of Edinburgh, LAAS-CNRS,
5 // Heriot-Watt University
6 // Copyright note valid unless otherwise stated in individual files.
7 // All rights reserved.
8 ///////////////////////////////////////////////////////////////////////////////
9
10 #include "action.hpp"
11
12 #include "cost.hpp"
13 #include "crocoddyl/core/actions/lqr.hpp"
14 #include "crocoddyl/core/actions/unicycle.hpp"
15 #include "crocoddyl/core/activations/quadratic-barrier.hpp"
16 #include "crocoddyl/core/activations/quadratic.hpp"
17 #include "crocoddyl/core/costs/residual.hpp"
18 #include "crocoddyl/core/utils/exception.hpp"
19 #include "crocoddyl/multibody/impulses/impulse-3d.hpp"
20 #include "crocoddyl/multibody/impulses/impulse-6d.hpp"
21 #include "crocoddyl/multibody/impulses/multiple-impulses.hpp"
22 #include "crocoddyl/multibody/residuals/contact-force.hpp"
23 #include "crocoddyl/multibody/residuals/contact-friction-cone.hpp"
24 #include "crocoddyl/multibody/residuals/contact-wrench-cone.hpp"
25 #include "impulse.hpp"
26
27 namespace crocoddyl {
28 namespace unittest {
29
30 const std::vector<ActionModelTypes::Type> ActionModelTypes::all(
31 ActionModelTypes::init_all());
32
33 71 std::ostream& operator<<(std::ostream& os, ActionModelTypes::Type type) {
34
7/9
✓ Branch 0 taken 13 times.
✓ Branch 1 taken 13 times.
✓ Branch 2 taken 13 times.
✓ Branch 3 taken 13 times.
✓ Branch 4 taken 13 times.
✓ Branch 5 taken 3 times.
✓ Branch 6 taken 3 times.
✗ Branch 7 not taken.
✗ Branch 8 not taken.
71 switch (type) {
35 13 case ActionModelTypes::ActionModelUnicycle:
36 13 os << "ActionModelUnicycle";
37 13 break;
38 13 case ActionModelTypes::ActionModelLQRDriftFree:
39 13 os << "ActionModelLQRDriftFree";
40 13 break;
41 13 case ActionModelTypes::ActionModelLQR:
42 13 os << "ActionModelLQR";
43 13 break;
44 13 case ActionModelTypes::ActionModelRandomLQR:
45 13 os << "ActionModelRandomLQR";
46 13 break;
47 13 case ActionModelTypes::ActionModelRandomLQRwithTerminalConstraint:
48 13 os << "ActionModelRandomLQRwithTerminalConstraint";
49 13 break;
50 3 case ActionModelTypes::ActionModelImpulseFwdDynamics_HyQ:
51 3 os << "ActionModelImpulseFwdDynamics_HyQ";
52 3 break;
53 3 case ActionModelTypes::ActionModelImpulseFwdDynamics_Talos:
54 3 os << "ActionModelImpulseFwdDynamics_Talos";
55 3 break;
56 case ActionModelTypes::NbActionModelTypes:
57 os << "NbActionModelTypes";
58 break;
59 default:
60 break;
61 }
62 71 return os;
63 }
64
65 208 ActionModelFactory::ActionModelFactory() {}
66 208 ActionModelFactory::~ActionModelFactory() {}
67
68 166 boost::shared_ptr<crocoddyl::ActionModelAbstract> ActionModelFactory::create(
69 ActionModelTypes::Type type, Instance instance) const {
70 166 boost::shared_ptr<crocoddyl::ActionModelAbstract> action;
71
7/8
✓ Branch 0 taken 28 times.
✓ Branch 1 taken 28 times.
✓ Branch 2 taken 28 times.
✓ Branch 3 taken 28 times.
✓ Branch 4 taken 28 times.
✓ Branch 5 taken 13 times.
✓ Branch 6 taken 13 times.
✗ Branch 7 not taken.
166 switch (type) {
72 28 case ActionModelTypes::ActionModelUnicycle:
73
1/2
✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
28 action = boost::make_shared<crocoddyl::ActionModelUnicycle>();
74 28 break;
75 28 case ActionModelTypes::ActionModelLQRDriftFree:
76
2/3
✓ Branch 0 taken 14 times.
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
28 switch (instance) {
77 14 case First:
78
1/2
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
14 action = boost::make_shared<crocoddyl::ActionModelLQR>(8, 2, true);
79 14 break;
80 14 case Second:
81 case Terminal:
82
1/2
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
14 action = boost::make_shared<crocoddyl::ActionModelLQR>(8, 4, true);
83 14 break;
84 }
85 case ActionModelTypes::ActionModelLQR:
86
2/3
✓ Branch 0 taken 28 times.
✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
56 switch (instance) {
87 28 case First:
88
1/2
✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
28 action = boost::make_shared<crocoddyl::ActionModelLQR>(8, 2, false);
89 28 break;
90 28 case Second:
91 case Terminal:
92
1/2
✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
28 action = boost::make_shared<crocoddyl::ActionModelLQR>(8, 4, false);
93 28 break;
94 }
95 56 break;
96 28 case ActionModelTypes::ActionModelRandomLQR:
97
2/3
✓ Branch 0 taken 14 times.
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
28 switch (instance) {
98 14 case First:
99
1/2
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
28 action = boost::make_shared<crocoddyl::ActionModelLQR>(
100
1/2
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
42 crocoddyl::ActionModelLQR::Random(8, 2));
101 14 break;
102 14 case Second:
103 case Terminal:
104
1/2
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
28 action = boost::make_shared<crocoddyl::ActionModelLQR>(
105
1/2
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
42 crocoddyl::ActionModelLQR::Random(8, 4));
106 14 break;
107 }
108 28 break;
109 28 case ActionModelTypes::ActionModelRandomLQRwithTerminalConstraint:
110
3/4
✓ Branch 0 taken 14 times.
✓ Branch 1 taken 7 times.
✓ Branch 2 taken 7 times.
✗ Branch 3 not taken.
28 switch (instance) {
111 14 case First:
112
1/2
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
28 action = boost::make_shared<crocoddyl::ActionModelLQR>(
113
1/2
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
42 crocoddyl::ActionModelLQR::Random(8, 2));
114 14 break;
115 7 case Second:
116
1/2
✓ Branch 1 taken 7 times.
✗ Branch 2 not taken.
14 action = boost::make_shared<crocoddyl::ActionModelLQR>(
117
1/2
✓ Branch 1 taken 7 times.
✗ Branch 2 not taken.
21 crocoddyl::ActionModelLQR::Random(8, 4));
118 7 break;
119 7 case Terminal:
120
1/2
✓ Branch 1 taken 7 times.
✗ Branch 2 not taken.
14 action = boost::make_shared<crocoddyl::ActionModelLQR>(
121
1/2
✓ Branch 1 taken 7 times.
✗ Branch 2 not taken.
21 crocoddyl::ActionModelLQR::Random(8, 4, 0, 2));
122 7 break;
123 }
124 28 break;
125 13 case ActionModelTypes::ActionModelImpulseFwdDynamics_HyQ:
126
1/2
✓ Branch 1 taken 13 times.
✗ Branch 2 not taken.
13 action = create_impulseFwdDynamics(StateModelTypes::StateMultibody_HyQ);
127 13 break;
128 13 case ActionModelTypes::ActionModelImpulseFwdDynamics_Talos:
129
1/2
✓ Branch 1 taken 13 times.
✗ Branch 2 not taken.
13 action = create_impulseFwdDynamics(StateModelTypes::StateMultibody_Talos);
130 13 break;
131 default:
132 throw_pretty(__FILE__ ": Wrong ActionModelTypes::Type given");
133 break;
134 }
135 166 return action;
136 }
137
138 boost::shared_ptr<crocoddyl::ActionModelImpulseFwdDynamics>
139 68 ActionModelFactory::create_impulseFwdDynamics(
140 StateModelTypes::Type state_type) const {
141 68 boost::shared_ptr<crocoddyl::ActionModelImpulseFwdDynamics> action;
142 68 boost::shared_ptr<crocoddyl::StateMultibody> state;
143 68 boost::shared_ptr<crocoddyl::ImpulseModelMultiple> impulse;
144 68 boost::shared_ptr<crocoddyl::CostModelSum> cost;
145 136 state = boost::static_pointer_cast<crocoddyl::StateMultibody>(
146
2/4
✓ Branch 1 taken 68 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 68 times.
✗ Branch 5 not taken.
204 StateModelFactory().create(state_type));
147
1/2
✓ Branch 1 taken 68 times.
✗ Branch 2 not taken.
68 impulse = boost::make_shared<crocoddyl::ImpulseModelMultiple>(state);
148
1/2
✓ Branch 1 taken 68 times.
✗ Branch 2 not taken.
68 cost = boost::make_shared<crocoddyl::CostModelSum>(state, 0);
149 68 double r_coeff = 0.; // TODO(cmastall): random_real_in_range(1e-16, 1e-2);
150 68 double damping = 0.; // TODO(cmastall): random_real_in_range(1e-16, 1e-2);
151
152
2/4
✓ Branch 1 taken 68 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 68 times.
✗ Branch 5 not taken.
68 Eigen::Matrix3d R = Eigen::Matrix3d::Identity();
153
1/2
✓ Branch 1 taken 68 times.
✗ Branch 2 not taken.
68 pinocchio::Force force = pinocchio::Force::Zero();
154
1/2
✓ Branch 2 taken 68 times.
✗ Branch 3 not taken.
68 crocoddyl::FrictionCone friction_cone(R, 0.8, 4, false);
155
1/2
✓ Branch 1 taken 68 times.
✗ Branch 2 not taken.
68 crocoddyl::WrenchCone wrench_cone(R, 0.8, Eigen::Vector2d(0.1, 0.1), 4,
156
1/2
✓ Branch 2 taken 68 times.
✗ Branch 3 not taken.
136 false);
157 68 crocoddyl::ActivationBounds friction_bounds(friction_cone.get_lb(),
158
1/2
✓ Branch 2 taken 68 times.
✗ Branch 3 not taken.
136 friction_cone.get_ub());
159 68 crocoddyl::ActivationBounds wrench_bounds(wrench_cone.get_lb(),
160
1/2
✓ Branch 2 taken 68 times.
✗ Branch 3 not taken.
136 wrench_cone.get_ub());
161 boost::shared_ptr<crocoddyl::ActivationModelAbstract> friction_activation =
162
1/2
✓ Branch 1 taken 68 times.
✗ Branch 2 not taken.
68 boost::make_shared<crocoddyl::ActivationModelQuadraticBarrier>(
163 68 friction_bounds);
164 boost::shared_ptr<crocoddyl::ActivationModelAbstract> wrench_activation =
165
1/2
✓ Branch 1 taken 68 times.
✗ Branch 2 not taken.
68 boost::make_shared<crocoddyl::ActivationModelQuadraticBarrier>(
166 68 wrench_bounds);
167
168
2/3
✓ Branch 0 taken 25 times.
✓ Branch 1 taken 43 times.
✗ Branch 2 not taken.
68 switch (state_type) {
169 25 case StateModelTypes::StateMultibody_HyQ:
170
5/10
✓ Branch 2 taken 25 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 25 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 25 times.
✗ Branch 10 not taken.
✓ Branch 13 taken 25 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 25 times.
✗ Branch 17 not taken.
25 impulse->addImpulse("lf", ImpulseModelFactory().create(
171 ImpulseModelTypes::ImpulseModel3D_LOCAL,
172 PinocchioModelTypes::HyQ, "lf_foot"));
173
5/10
✓ Branch 2 taken 25 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 25 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 25 times.
✗ Branch 10 not taken.
✓ Branch 13 taken 25 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 25 times.
✗ Branch 17 not taken.
25 impulse->addImpulse("rf", ImpulseModelFactory().create(
174 ImpulseModelTypes::ImpulseModel3D_WORLD,
175 PinocchioModelTypes::HyQ, "rf_foot"));
176
5/10
✓ Branch 2 taken 25 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 25 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 25 times.
✗ Branch 10 not taken.
✓ Branch 13 taken 25 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 25 times.
✗ Branch 17 not taken.
25 impulse->addImpulse("lh", ImpulseModelFactory().create(
177 ImpulseModelTypes::ImpulseModel3D_LWA,
178 PinocchioModelTypes::HyQ, "lh_foot"));
179
5/10
✓ Branch 2 taken 25 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 25 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 25 times.
✗ Branch 10 not taken.
✓ Branch 13 taken 25 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 25 times.
✗ Branch 17 not taken.
25 impulse->addImpulse("rh", ImpulseModelFactory().create(
180 ImpulseModelTypes::ImpulseModel3D_LOCAL,
181 PinocchioModelTypes::HyQ, "rh_foot"));
182
183 // friction cone
184
2/4
✓ Branch 4 taken 25 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 25 times.
✗ Branch 8 not taken.
50 cost->addCost(
185 "lf_cone",
186
1/2
✓ Branch 1 taken 25 times.
✗ Branch 2 not taken.
50 boost::make_shared<crocoddyl::CostModelResidual>(
187 state, friction_activation,
188 25 boost::make_shared<crocoddyl::ResidualModelContactFrictionCone>(
189
3/6
✓ Branch 4 taken 25 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 25 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 25 times.
✗ Branch 11 not taken.
50 state, state->get_pinocchio()->getFrameId("lf_foot"),
190 25 friction_cone, 0)),
191 0.1);
192
2/4
✓ Branch 4 taken 25 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 25 times.
✗ Branch 8 not taken.
50 cost->addCost(
193 "rf_cone",
194
1/2
✓ Branch 1 taken 25 times.
✗ Branch 2 not taken.
50 boost::make_shared<crocoddyl::CostModelResidual>(
195 state, friction_activation,
196 25 boost::make_shared<crocoddyl::ResidualModelContactFrictionCone>(
197
3/6
✓ Branch 4 taken 25 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 25 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 25 times.
✗ Branch 11 not taken.
50 state, state->get_pinocchio()->getFrameId("rf_foot"),
198 25 friction_cone, 0)),
199 0.1);
200
2/4
✓ Branch 4 taken 25 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 25 times.
✗ Branch 8 not taken.
50 cost->addCost(
201 "lh_cone",
202
1/2
✓ Branch 1 taken 25 times.
✗ Branch 2 not taken.
50 boost::make_shared<crocoddyl::CostModelResidual>(
203 state, friction_activation,
204 25 boost::make_shared<crocoddyl::ResidualModelContactFrictionCone>(
205
3/6
✓ Branch 4 taken 25 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 25 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 25 times.
✗ Branch 11 not taken.
50 state, state->get_pinocchio()->getFrameId("lh_foot"),
206 25 friction_cone, 0)),
207 0.1);
208
2/4
✓ Branch 4 taken 25 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 25 times.
✗ Branch 8 not taken.
50 cost->addCost(
209 "rh_cone",
210
1/2
✓ Branch 1 taken 25 times.
✗ Branch 2 not taken.
50 boost::make_shared<crocoddyl::CostModelResidual>(
211 state, friction_activation,
212 25 boost::make_shared<crocoddyl::ResidualModelContactFrictionCone>(
213
3/6
✓ Branch 4 taken 25 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 25 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 25 times.
✗ Branch 11 not taken.
50 state, state->get_pinocchio()->getFrameId("rh_foot"),
214 25 friction_cone, 0)),
215 0.1);
216 // force regularization
217
2/4
✓ Branch 4 taken 25 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 25 times.
✗ Branch 8 not taken.
50 cost->addCost(
218 "lf_forceReg",
219
1/2
✓ Branch 1 taken 25 times.
✗ Branch 2 not taken.
50 boost::make_shared<crocoddyl::CostModelResidual>(
220 25 state, boost::make_shared<crocoddyl::ResidualModelContactForce>(
221
3/6
✓ Branch 4 taken 25 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 25 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 25 times.
✗ Branch 11 not taken.
50 state, state->get_pinocchio()->getFrameId("lf_foot"),
222 25 force, 3, 0)),
223 0.1);
224
2/4
✓ Branch 4 taken 25 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 25 times.
✗ Branch 8 not taken.
50 cost->addCost(
225 "rf_forceReg",
226
1/2
✓ Branch 1 taken 25 times.
✗ Branch 2 not taken.
50 boost::make_shared<crocoddyl::CostModelResidual>(
227 25 state, boost::make_shared<crocoddyl::ResidualModelContactForce>(
228
3/6
✓ Branch 4 taken 25 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 25 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 25 times.
✗ Branch 11 not taken.
50 state, state->get_pinocchio()->getFrameId("rf_foot"),
229 25 force, 3, 0)),
230 0.1);
231
2/4
✓ Branch 4 taken 25 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 25 times.
✗ Branch 8 not taken.
50 cost->addCost(
232 "lh_forceReg",
233
1/2
✓ Branch 1 taken 25 times.
✗ Branch 2 not taken.
50 boost::make_shared<crocoddyl::CostModelResidual>(
234 25 state, boost::make_shared<crocoddyl::ResidualModelContactForce>(
235
3/6
✓ Branch 4 taken 25 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 25 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 25 times.
✗ Branch 11 not taken.
50 state, state->get_pinocchio()->getFrameId("lh_foot"),
236 25 force, 3, 0)),
237 0.1);
238
2/4
✓ Branch 4 taken 25 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 25 times.
✗ Branch 8 not taken.
50 cost->addCost(
239 "rh_forceReg",
240
1/2
✓ Branch 1 taken 25 times.
✗ Branch 2 not taken.
50 boost::make_shared<crocoddyl::CostModelResidual>(
241 25 state, boost::make_shared<crocoddyl::ResidualModelContactForce>(
242
3/6
✓ Branch 4 taken 25 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 25 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 25 times.
✗ Branch 11 not taken.
50 state, state->get_pinocchio()->getFrameId("rh_foot"),
243 25 force, 3, 0)),
244 0.1);
245 25 break;
246 43 case StateModelTypes::StateMultibody_Talos:
247
2/4
✓ Branch 3 taken 43 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 43 times.
✗ Branch 7 not taken.
86 impulse->addImpulse("lf",
248
3/6
✓ Branch 1 taken 43 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 43 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 43 times.
✗ Branch 9 not taken.
86 ImpulseModelFactory().create(
249 ImpulseModelTypes::ImpulseModel6D_LOCAL,
250 PinocchioModelTypes::Talos, "left_sole_link"));
251
2/4
✓ Branch 3 taken 43 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 43 times.
✗ Branch 7 not taken.
86 impulse->addImpulse("rf",
252
3/6
✓ Branch 1 taken 43 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 43 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 43 times.
✗ Branch 9 not taken.
86 ImpulseModelFactory().create(
253 ImpulseModelTypes::ImpulseModel6D_WORLD,
254 PinocchioModelTypes::Talos, "right_sole_link"));
255
256 // friction / wrench cone
257
2/4
✓ Branch 4 taken 43 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 43 times.
✗ Branch 8 not taken.
86 cost->addCost(
258 "lf_cone",
259
1/2
✓ Branch 1 taken 43 times.
✗ Branch 2 not taken.
86 boost::make_shared<crocoddyl::CostModelResidual>(
260 state, friction_activation,
261 43 boost::make_shared<crocoddyl::ResidualModelContactFrictionCone>(
262
3/6
✓ Branch 4 taken 43 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 43 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 43 times.
✗ Branch 11 not taken.
86 state, state->get_pinocchio()->getFrameId("left_sole_link"),
263 43 friction_cone, 0)),
264 0.01);
265
2/4
✓ Branch 4 taken 43 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 43 times.
✗ Branch 8 not taken.
86 cost->addCost(
266 "rf_cone",
267
1/2
✓ Branch 1 taken 43 times.
✗ Branch 2 not taken.
86 boost::make_shared<crocoddyl::CostModelResidual>(
268 state, wrench_activation,
269 43 boost::make_shared<crocoddyl::ResidualModelContactWrenchCone>(
270
3/6
✓ Branch 4 taken 43 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 43 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 43 times.
✗ Branch 11 not taken.
86 state, state->get_pinocchio()->getFrameId("right_sole_link"),
271 43 wrench_cone, 0)),
272 0.01);
273 // force regularization
274
2/4
✓ Branch 4 taken 43 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 43 times.
✗ Branch 8 not taken.
86 cost->addCost(
275 "lf_forceReg",
276
1/2
✓ Branch 1 taken 43 times.
✗ Branch 2 not taken.
86 boost::make_shared<crocoddyl::CostModelResidual>(
277 state,
278 43 boost::make_shared<crocoddyl::ResidualModelContactForce>(
279
3/6
✓ Branch 4 taken 43 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 43 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 43 times.
✗ Branch 11 not taken.
86 state, state->get_pinocchio()->getFrameId("left_sole_link"),
280 43 force, 6, 0)),
281 0.01);
282
2/4
✓ Branch 4 taken 43 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 43 times.
✗ Branch 8 not taken.
86 cost->addCost(
283 "rf_forceReg",
284
1/2
✓ Branch 1 taken 43 times.
✗ Branch 2 not taken.
86 boost::make_shared<crocoddyl::CostModelResidual>(
285 state,
286 43 boost::make_shared<crocoddyl::ResidualModelContactForce>(
287
3/6
✓ Branch 4 taken 43 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 43 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 43 times.
✗ Branch 11 not taken.
86 state, state->get_pinocchio()->getFrameId("right_sole_link"),
288 43 force, 6, 0)),
289 0.01);
290 43 break;
291 default:
292 throw_pretty(__FILE__ ": Wrong StateModelTypes::Type given");
293 break;
294 }
295
2/4
✓ Branch 3 taken 68 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 68 times.
✗ Branch 7 not taken.
136 cost->addCost("state",
296
2/4
✓ Branch 1 taken 68 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 68 times.
✗ Branch 5 not taken.
136 CostModelFactory().create(
297 CostModelTypes::CostModelResidualState, state_type,
298 ActivationModelTypes::ActivationModelQuad, 0),
299 0.1);
300 68 action = boost::make_shared<crocoddyl::ActionModelImpulseFwdDynamics>(
301
1/2
✓ Branch 1 taken 68 times.
✗ Branch 2 not taken.
68 state, impulse, cost, r_coeff, damping, true);
302 136 return action;
303 68 }
304
305 } // namespace unittest
306 } // namespace crocoddyl
307