GCC Code Coverage Report


Directory: ./
File: benchmark/quadruped.cpp
Date: 2024-12-02 00:24:10
Exec Total Coverage
Lines: 0 134 0.0%
Branches: 0 702 0.0%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // BSD 3-Clause License
3 //
4 // Copyright (C) 2018-2019, LAAS-CNRS
5 // Copyright note valid unless otherwise stated in individual files.
6 // All rights reserved.
7 ///////////////////////////////////////////////////////////////////////////////
8
9 #include <quadruped-walkgen/quadruped.hpp>
10
11 #include "crocoddyl/core/actions/unicycle.hpp"
12 #include "crocoddyl/core/solvers/ddp.hpp"
13 #include "crocoddyl/core/utils/callbacks.hpp"
14 #include "crocoddyl/core/utils/timer.hpp"
15
16 void updateModel(
17 std::vector<boost::shared_ptr<quadruped_walkgen::ActionModelQuadruped> >
18 running_models_2,
19 boost::shared_ptr<quadruped_walkgen::ActionModelQuadruped> terminal_model_2,
20 Eigen::Matrix<double, 6, 5> gait, Eigen::Matrix<double, 12, 17> xref,
21 Eigen::Matrix<double, 6, 13> fsteps, int N) {
22 // Iterate over all the phases of the gait matrix
23 // The first column of xref correspond to the current state = x0
24 // Tmp is needed to use .data(), transformation of a column into a vector
25 Eigen::Array<double, 1, 12> tmp = Eigen::Array<double, 1, 12>::Zero();
26 int max_index = int(gait.block(0, 0, 6, 1).array().min(1.).matrix().sum());
27 int k_cum = 0;
28
29 for (int j = 0; j < max_index; j++) {
30 for (int k = k_cum; k < k_cum + int(gait(j, 0)); ++k) {
31 if (k < int(N)) {
32 // Update model :
33 tmp = fsteps.block(j, 1, 1, 12).array();
34 running_models_2[k]->update_model(
35 Eigen::Map<Eigen::Matrix<double, 3, 4> >(tmp.data(), 3, 4),
36 Eigen::Map<Eigen::Matrix<double, 12, 1> >(
37 xref.block(0, k + 1, 12, 1).data(), 12, 1),
38 Eigen::Map<Eigen::Matrix<double, 4, 1> >(
39 gait.block(j, 1, 1, 4).data(), 4, 1));
40 }
41 }
42 k_cum += int(gait(j, 0));
43 }
44
45 tmp = fsteps.block(max_index - 1, 1, 1, 12).array();
46 Eigen::Array<double, 1, 4> gait_tmp = Eigen::Array<double, 1, 4>::Zero();
47 gait_tmp = gait.block(max_index - 1, 1, 1, 4).array();
48
49 terminal_model_2->update_model(
50 Eigen::Map<Eigen::Matrix<double, 3, 4> >(tmp.data(), 3, 4),
51 Eigen::Map<Eigen::Matrix<double, 12, 1> >(xref.block(0, 16, 12, 1).data(),
52 12, 1),
53 Eigen::Map<Eigen::Matrix<double, 4, 1> >(gait_tmp.data(), 4, 1));
54 terminal_model_2->set_force_weights(Eigen::Matrix<double, 12, 1>::Zero());
55 terminal_model_2->set_friction_weight(0);
56 }
57
58 int main(int argc, char* argv[]) {
59 // The time of the cycle contol is 0.02s, and last 0.32s --> 16nodes
60 // Control cycle during one gait period
61 unsigned int N = 16; // number of nodes
62 unsigned int T = 1000; // number of trials
63 unsigned int MAXITER = 1;
64 if (argc > 1) {
65 T = atoi(argv[1]);
66 MAXITER = atoi(argv[2]);
67 ;
68 }
69
70 // Creating the initial state vector (size x12)
71 // [x,y,z,Roll,Pitch,Yaw,Vx,Vy,Vz,Wroll,Wpitch,Wyaw] Perturbation of Vx =
72 // 0.2m.s-1
73 Eigen::Matrix<double, 12, 1> x0;
74 x0 << 0, 0, 0.2, 0, 0, 0, 0.2, 0, 0, 0, 0, 0;
75 Eigen::Matrix<double, 4, 1> S;
76 S << 1, 0, 0, 1;
77
78 // Creating the reference state vector (size 12x16) to follow during the
79 // control cycle Nullifying the Vx speed.
80 Eigen::Matrix<double, 12, 1> xref_vector;
81 xref_vector << 0, 0, 0.2, 0, 0, 0, 0, 0, 0, 0, 0, 0;
82 Eigen::Matrix<double, 12, 17> xref;
83 xref.block(0, 0, 12, 1) = x0; // first vector is the initial state
84 xref.block(0, 1, 12, 16) = xref_vector.replicate<1, 16>();
85
86 // Creating the gait matrix : The number at the beginning represents the
87 // number of node spent in that position 1 -> foot in contact with the ground
88 // : 0-> foot in the air
89 Eigen::Matrix<double, 6, 5> gait;
90 gait << 1, 1, 1, 1, 1, 7, 1, 0, 0, 1, 1, 1, 1, 1, 1, 7, 0, 1, 1, 0, 0, 0, 0,
91 0, 0, 0, 0, 0, 0, 0;
92
93 // Creating the fsteps matrix that represents the position of the feet during
94 // the whole control cycle (0.32s). [nb , x1,y1,z1, x2,y2,z2 ...] in local
95 // frame The number at the beginning represents the number of node spent in
96 // that position Here, the robot starts with 4 feet on the ground at the first
97 // node, then during 7 nodes (0.02s * 7) The leg right front leg and left back
98 // leg are in the air ...etc
99
100 Eigen::Matrix<double, 6, 13> fsteps;
101 fsteps << 1, 0.19, 0.15, 0.0, 0.19, -0.15, 0.0, -0.19, 0.15, 0.0, -0.19,
102 -0.15, 0.0, 7, 0.19, 0.15, 0.0, 0, 0, 0, 0, 0, 0, -0.19, -0.15, 0.0, 1,
103 0.19, 0.15, 0.0, 0.19, -0.15, 0.0, -0.19, 0.15, 0.0, -0.19, -0.15, 0.0, 7,
104 0, 0, 0, 0.19, -0.15, 0.0, -0.19, 0.15, 0.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
105 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0;
106
107 // Creating the Shoting problem that needs
108 // boost::shared_ptr<crocoddyl::ActionModelAbstract>
109
110 // Cannot use 1 model for the whole control cycle, because each model depends
111 // on the position of the feet And the inertia matrix depends on the reference
112 // state (approximation )
113 std::vector<boost::shared_ptr<crocoddyl::ActionModelAbstract> >
114 running_models;
115
116 for (int i = 0; i < int(N); ++i) { // 16 nodes
117 boost::shared_ptr<crocoddyl::ActionModelAbstract> model =
118 boost::make_shared<quadruped_walkgen::ActionModelQuadruped>();
119 running_models.push_back(model);
120 }
121
122 boost::shared_ptr<crocoddyl::ActionModelAbstract> terminal_model;
123 terminal_model =
124 boost::make_shared<quadruped_walkgen::ActionModelQuadruped>();
125
126 // Update each model and set to 0 the weight ont the command for the terminal
127 // node For that, the internal method of
128 // quadruped_walkgen::ActionModelQuadruped needs to be accessed
129 // -> Creation of a 2nd list using dynamic_cast
130
131 int k_cum = 0;
132 std::vector<boost::shared_ptr<quadruped_walkgen::ActionModelQuadruped> >
133 running_models_2;
134
135 // Iterate over all the phases of the gait matrix
136 // The first column of xref correspond to the current state = x0
137 // Tmp is needed to use .data(), transformation of a column into a vector
138 Eigen::Array<double, 1, 12> tmp = Eigen::Array<double, 1, 12>::Zero();
139 int max_index = int(gait.block(0, 0, 6, 1).array().min(1.).matrix().sum());
140
141 for (int j = 0; j < max_index; j++) {
142 for (int k = k_cum; k < k_cum + int(gait(j, 0)); ++k) {
143 if (k < int(N)) {
144 boost::shared_ptr<quadruped_walkgen::ActionModelQuadruped> model2 =
145 boost::dynamic_pointer_cast<
146 quadruped_walkgen::ActionModelQuadruped>(running_models[k]);
147 running_models_2.push_back(model2);
148
149 // Update model :
150 tmp = fsteps.block(j, 1, 1, 12).array();
151 model2->update_model(
152 Eigen::Map<Eigen::Matrix<double, 3, 4> >(tmp.data(), 3, 4),
153 Eigen::Map<Eigen::Matrix<double, 12, 1> >(
154 xref.block(0, k + 1, 12, 1).data(), 12, 1),
155 Eigen::Map<Eigen::Matrix<double, 4, 1> >(
156 gait.block(j, 1, 1, 4).data(), 4, 1));
157 }
158 }
159 k_cum += int(gait(j, 0));
160 }
161
162 boost::shared_ptr<quadruped_walkgen::ActionModelQuadruped> terminal_model_2 =
163 boost::dynamic_pointer_cast<quadruped_walkgen::ActionModelQuadruped>(
164 terminal_model);
165
166 tmp = fsteps.block(max_index - 1, 1, 1, 12).array();
167 Eigen::Array<double, 1, 4> gait_tmp = Eigen::Array<double, 1, 4>::Zero();
168 gait_tmp = gait.block(max_index - 1, 1, 1, 4).array();
169
170 terminal_model_2->update_model(
171 Eigen::Map<Eigen::Matrix<double, 3, 4> >(tmp.data(), 3, 4),
172 Eigen::Map<Eigen::Matrix<double, 12, 1> >(xref.block(0, 16, 12, 1).data(),
173 12, 1),
174 Eigen::Map<Eigen::Matrix<double, 4, 1> >(gait_tmp.data(), 4, 1));
175 terminal_model_2->set_force_weights(Eigen::Matrix<double, 12, 1>::Zero());
176 terminal_model_2->set_friction_weight(0);
177
178 boost::shared_ptr<crocoddyl::ShootingProblem> problem =
179 boost::make_shared<crocoddyl::ShootingProblem>(x0, running_models,
180 terminal_model);
181 crocoddyl::SolverDDP ddp(problem);
182
183 std::vector<Eigen::VectorXd> xs(int(N) + 1, x0);
184 Eigen::Matrix<double, 12, 1> u0;
185 u0 << 1, 0.2, 0.5, 1, 1, -0.2, -1, 1, 0.5, -1, -1, -0.5;
186 std::vector<Eigen::VectorXd> us(int(N), u0);
187
188 Eigen::ArrayXd duration(T);
189
190 // Updating the problem
191 for (unsigned int i = 0; i < T; ++i) {
192 crocoddyl::Timer timer;
193 updateModel(running_models_2, terminal_model_2, gait, xref, fsteps, N);
194 duration[i] = timer.get_duration();
195 }
196 double avrg_duration = duration.sum() / T;
197 double min_duration = duration.minCoeff();
198 double max_duration = duration.maxCoeff();
199 std::cout << " UpdateModel [ms]: " << avrg_duration << " (" << min_duration
200 << "-" << max_duration << ")" << std::endl;
201
202 // Solving the optimal control problem
203 for (unsigned int i = 0; i < T; ++i) {
204 crocoddyl::Timer timer;
205 ddp.solve(xs, us, MAXITER);
206 duration[i] = timer.get_duration();
207 }
208
209 avrg_duration = duration.sum() / T;
210 min_duration = duration.minCoeff();
211 max_duration = duration.maxCoeff();
212 std::cout << " DDP.solve [ms]: " << avrg_duration << " (" << min_duration
213 << "-" << max_duration << ")" << std::endl;
214
215 // Solving the optimal control problem
216 for (unsigned int i = 0; i < T; ++i) {
217 crocoddyl::Timer timer;
218 ddp.solve(xs, us, MAXITER);
219 duration[i] = timer.get_duration();
220 }
221
222 avrg_duration = duration.sum() / T;
223 min_duration = duration.minCoeff();
224 max_duration = duration.maxCoeff();
225 std::cout << " DDP.solve [ms]: " << avrg_duration << " (" << min_duration
226 << "-" << max_duration << ")" << std::endl;
227
228 // Running calc
229 for (unsigned int i = 0; i < T; ++i) {
230 crocoddyl::Timer timer;
231 problem->calc(xs, us);
232 duration[i] = timer.get_duration();
233 }
234
235 avrg_duration = duration.sum() / T;
236 min_duration = duration.minCoeff();
237 max_duration = duration.maxCoeff();
238 std::cout << " ShootingProblem.calc [ms]: " << avrg_duration << " ("
239 << min_duration << "-" << max_duration << ")" << std::endl;
240
241 // Running calcDiff
242 for (unsigned int i = 0; i < T; ++i) {
243 crocoddyl::Timer timer;
244 problem->calcDiff(xs, us);
245 duration[i] = timer.get_duration();
246 }
247
248 avrg_duration = duration.sum() / T;
249 min_duration = duration.minCoeff();
250 max_duration = duration.maxCoeff();
251 std::cout << " ShootingProblem.calcDiff [ms]: " << avrg_duration << " ("
252 << min_duration << "-" << max_duration << ")" << std::endl;
253 }
254