GCC Code Coverage Report


Directory: ./
File: benchmark/quadruped-planner.cpp
Date: 2024-12-02 00:24:10
Exec Total Coverage
Lines: 0 128 0.0%
Branches: 0 588 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 "crocoddyl/core/codegen/action-base.hpp"
10
11 #include <quadruped-walkgen/quadruped_augmented.hpp>
12 #include <quadruped-walkgen/quadruped_step.hpp>
13 #include <quadruped-walkgen/quadruped_step_time.hpp>
14 #include <quadruped-walkgen/quadruped_time.hpp>
15
16 #include "crocoddyl/core/actions/unicycle.hpp"
17 #include "crocoddyl/core/solvers/ddp.hpp"
18 #include "crocoddyl/core/utils/callbacks.hpp"
19 #include "crocoddyl/core/utils/timer.hpp"
20
21 #define STDDEV(vec) \
22 std::sqrt(((vec - vec.mean())).square().sum() / (double(vec.size()) - 1.))
23 #define AVG(vec) (vec.mean())
24
25 int main(int argc, char* argv[]) {
26 // The time of the cycle contol is 0.02s, and last 0.32s --> 16nodes
27 // Control cycle during one gait period
28 unsigned int N = 16; // number of nodes
29 unsigned int T = 1000; // number of trials
30 unsigned int MAXITER = 1;
31 if (argc > 1) {
32 T = atoi(argv[1]);
33 MAXITER = atoi(argv[2]);
34 ;
35 }
36
37 boost::shared_ptr<crocoddyl::ActionModelAbstract> model_test;
38 model_test =
39 boost::make_shared<quadruped_walkgen::ActionModelQuadrupedStepTime>();
40
41 // Creating the initial state vector (size x12)
42 // [x,y,z,Roll,Pitch,Yaw,Vx,Vy,Vz,Wroll,Wpitch,Wyaw] Perturbation of Vx =
43 // 0.2m.s-1
44 Eigen::Matrix<double, 20, 1> x0;
45 x0 << 0., 0., 0.2, 0., 0., 0., 0.2, 0., 0., 0., 0., 0., 0.1946, 0.15005,
46 0.204, -0.137, -0.184, 0.14, -0.1946, -0.1505;
47 Eigen::Matrix<double, 4, 1> S;
48 S << 0, 1, 1, 0;
49
50 Eigen::Matrix<double, 3, 4> l_feet; // computed by previous gait cycle
51 l_feet << 0.1946, 0.21, -0.18, -0.19, 0.15, -0.16, 0.145, -0.135, 0.0, 0.0,
52 0.0, 0.0;
53
54 // Creating the reference state vector (size 12x16) to follow during the
55 // control cycle Nullifying the Vx speed.
56 Eigen::Matrix<double, 12, 1> xref_vector;
57 xref_vector << 0., 0., 0.2, 0., 0., 0., 0., 0., 0., 0., 0., 0.;
58 Eigen::Matrix<double, 12, 17> xref;
59 xref.block(0, 0, 12, 1) << 0., 0., 0.2, 0., 0., 0., 0.1, 0., 0., 0., 0.,
60 0.; // first vector is the initial state
61 xref.block(0, 1, 12, 16) = xref_vector.replicate<1, 16>();
62
63 // Creating the gait matrix : The number at the beginning represents the
64 // number of node spent in that position 1 -> foot in contact with the ground
65 // : 0-> foot in the air
66 Eigen::Matrix<double, 6, 5> gait;
67 gait << 7, 0, 1, 1, 0, 1, 1, 1, 1, 1, 7, 1, 0, 0, 1, 1, 1, 1, 1, 1, 0, 0, 0,
68 0, 0, 0, 0, 0, 0, 0;
69
70 // Creating the Shoting problem that needs
71 // boost::shared_ptr<crocoddyl::ActionModelAbstract>
72
73 // Cannot use 1 model for the whole control cycle, because each model depends
74 // on the position of the feet And the inertia matrix depends on the reference
75 // state (approximation )
76 std::vector<boost::shared_ptr<crocoddyl::ActionModelAbstract> >
77 running_models;
78
79 int max_index = int(gait.block(0, 0, 6, 1).array().min(1.).matrix().sum());
80 int k_cum = 0;
81 for (int j = 0; j < max_index; j++) {
82 for (int k = k_cum; k < k_cum + int(gait(j, 0)); ++k) {
83 if (k < int(N)) {
84 if (int(gait.block(j, 1, 1, 4).sum()) == 4) {
85 boost::shared_ptr<crocoddyl::ActionModelAbstract> model =
86 boost::make_shared<quadruped_walkgen::ActionModelQuadrupedStep>();
87 running_models.push_back(model);
88 }
89 boost::shared_ptr<crocoddyl::ActionModelAbstract> model =
90 boost::make_shared<
91 quadruped_walkgen::ActionModelQuadrupedAugmented>();
92 running_models.push_back(model);
93 }
94 }
95 k_cum += int(gait(j, 0));
96 }
97
98 boost::shared_ptr<crocoddyl::ActionModelAbstract> terminal_model;
99 terminal_model =
100 boost::make_shared<quadruped_walkgen::ActionModelQuadrupedAugmented>();
101
102 // Update each model and set to 0 the weight ont the command for the terminal
103 // node For that, the internal method of
104 // quadruped_walkgen::ActionModelQuadruped needs to be accessed
105 // -> Creation of a 2nd list using dynamic_cast
106
107 k_cum = 0;
108 Eigen::Matrix<double, 12, 1> u0;
109 u0 << 1, 0.2, 8, 1, 1, 8, -1, 1, 8, -1, -1, 8;
110 std::vector<Eigen::VectorXd> us;
111 Eigen::Matrix<double, 4, 1> u0_step;
112 u0_step << 0.05, 0.01, 0.02, 0.06;
113
114 // Iterate over all the phases of the gait matrix
115 // The first column of xref correspond to the current state = x0
116 // Tmp is needed to use .data(), transformation of a column into a vector
117 Eigen::Array<double, 3, 4> tmp = Eigen::Array<double, 3, 4>::Zero();
118 Eigen::Matrix<double, 1, 4> S_tmp;
119 S_tmp.setZero();
120
121 int gap = 0;
122 for (int j = 0; j < max_index; j++) {
123 for (int k = k_cum; k < k_cum + int(gait(j, 0)); ++k) {
124 if (k < int(N)) {
125 if (int(gait.block(j, 1, 1, 4).sum()) == 4) {
126 boost::shared_ptr<quadruped_walkgen::ActionModelQuadrupedStep>
127 model3 = boost::dynamic_pointer_cast<
128 quadruped_walkgen::ActionModelQuadrupedStep>(
129 running_models[k + gap]);
130
131 tmp = l_feet.array();
132 S_tmp = gait.block(j, 1, 1, 4) - gait.block(j - 1, 1, 1, 4);
133 model3->update_model(
134 Eigen::Map<Eigen::Matrix<double, 3, 4> >(tmp.data(), 3, 4),
135 Eigen::Map<Eigen::Matrix<double, 12, 1> >(
136 xref.block(0, k, 12, 1).data(), 12, 1),
137 Eigen::Map<Eigen::Matrix<double, 4, 1> >(S_tmp.data(), 4, 1),
138 Eigen::Matrix<double, 3, 4>::Zero(),
139 Eigen::Matrix<double, 3, 4>::Zero(),
140 Eigen::Matrix<double, 3, 4>::Zero(),
141 Eigen::Matrix<double, 3, 4>::Zero(),
142 Eigen::Matrix<double, 3, 3>::Zero(),
143 Eigen::Matrix<double, 3, 1>::Zero(), 0.16);
144
145 gap = gap + 1;
146 us.push_back(u0_step);
147 }
148 // std::cout << "indice :" << gap << std::endl ;
149
150 boost::shared_ptr<quadruped_walkgen::ActionModelQuadrupedAugmented>
151 model2 = boost::dynamic_pointer_cast<
152 quadruped_walkgen::ActionModelQuadrupedAugmented>(
153 running_models[k + gap]);
154
155 // Update model :
156 tmp = l_feet.array();
157 if (int(gait.block(j, 1, 1, 4).sum()) == 4 and gap == 1) {
158 model2->set_stop_weights(Eigen::Matrix<double, 8, 1>::Constant(1));
159 } else {
160 model2->set_stop_weights(Eigen::Matrix<double, 8, 1>::Zero());
161 }
162 model2->update_model(
163 Eigen::Map<Eigen::Matrix<double, 3, 4> >(tmp.data(), 3, 4),
164 Eigen::Map<Eigen::Matrix<double, 3, 4> >(tmp.data(), 3, 4),
165 Eigen::Map<Eigen::Matrix<double, 12, 1> >(
166 xref.block(0, k + 1, 12, 1).data(), 12, 1),
167 Eigen::Map<Eigen::Matrix<double, 4, 1> >(
168 gait.block(j, 1, 1, 4).data(), 4, 1));
169 us.push_back(u0);
170 }
171 }
172 k_cum += int(gait(j, 0));
173 }
174
175 boost::shared_ptr<quadruped_walkgen::ActionModelQuadrupedAugmented>
176 terminal_model_2 = boost::dynamic_pointer_cast<
177 quadruped_walkgen::ActionModelQuadrupedAugmented>(terminal_model);
178
179 tmp = l_feet.array();
180 Eigen::Array<double, 1, 4> gait_tmp = Eigen::Array<double, 1, 4>::Zero();
181 gait_tmp = gait.block(max_index - 1, 1, 1, 4).array();
182
183 terminal_model_2->update_model(
184 Eigen::Map<Eigen::Matrix<double, 3, 4> >(tmp.data(), 3, 4),
185 Eigen::Map<Eigen::Matrix<double, 3, 4> >(tmp.data(), 3, 4),
186 Eigen::Map<Eigen::Matrix<double, 12, 1> >(xref.block(0, 16, 12, 1).data(),
187 12, 1),
188 Eigen::Map<Eigen::Matrix<double, 4, 1> >(gait_tmp.data(), 4, 1));
189 terminal_model_2->set_force_weights(Eigen::Matrix<double, 12, 1>::Zero());
190 terminal_model_2->set_friction_weight(0);
191 terminal_model_2->set_stop_weights(Eigen::Matrix<double, 8, 1>::Zero());
192
193 ////////////////////////////////////
194 // Code gen
195 // ////////////////////////////////////
196
197 // typedef CppAD::AD<CppAD::cg::CG<double> > ADScalar;
198
199 // // Code generation of the running an terminal models
200 // boost::shared_ptr<crocoddyl::ActionModelAbstractTpl<ADScalar> >
201 // ad_runningModel, ad_terminalModel;
202 // crocoddyl::benchmark::build_arm_action_models(ad_runningModel,
203 // ad_terminalModel); boost::shared_ptr<crocoddyl::ActionModelAbstract>
204 // cg_runningModel =
205 // boost::make_shared<crocoddyl::ActionModelCodeGen>(ad_runningModel,
206 // runningModel, "arm_manipulation_running_cg");
207 // boost::shared_ptr<crocoddyl::ActionModelAbstract> cg_terminalModel =
208 // boost::make_shared<crocoddyl::ActionModelCodeGen>(ad_terminalModel,
209 // terminalModel,
210 // "arm_manipulation_terminal_cg");
211
212 // for (int k = 0 ; k < running_models.size() ; j++ ) {
213
214 // }
215
216 std::cout << running_models.size() << std::endl;
217
218 boost::shared_ptr<crocoddyl::ShootingProblem> problem =
219 boost::make_shared<crocoddyl::ShootingProblem>(x0, running_models,
220 terminal_model);
221 crocoddyl::SolverDDP ddp(problem);
222
223 std::vector<Eigen::VectorXd> xs(running_models.size() + 1, x0);
224 // Eigen::Matrix<double,12,1> u0 ;
225 // u0 << 1,0.2,8, 1,1,8, -1,1,8, -1,-1,8;
226 // std::vector<Eigen::VectorXd> us(int(N), u0);
227
228 Eigen::ArrayXd duration(T);
229
230 // Solving the optimal control problem
231 for (unsigned int i = 0; i < T; ++i) {
232 crocoddyl::Timer timer;
233 ddp.solve(xs, us, MAXITER);
234 duration[i] = timer.get_duration();
235 }
236
237 double avrg_duration = duration.sum() / T;
238 double min_duration = duration.minCoeff();
239 double max_duration = duration.maxCoeff();
240 std::cout << " DDP.solve [ms]: " << avrg_duration << " (" << min_duration
241 << "-" << max_duration << ")" << std::endl;
242
243 // Running calc
244 for (unsigned int i = 0; i < T; ++i) {
245 crocoddyl::Timer timer;
246 problem->calc(xs, us);
247 duration[i] = timer.get_duration();
248 }
249
250 avrg_duration = duration.sum() / T;
251 min_duration = duration.minCoeff();
252 max_duration = duration.maxCoeff();
253 std::cout << " ShootingProblem.calc [ms]: " << avrg_duration << " ("
254 << min_duration << "-" << max_duration << ")" << std::endl;
255
256 // Running calcDiff
257 for (unsigned int i = 0; i < T; ++i) {
258 crocoddyl::Timer timer;
259 problem->calcDiff(xs, us);
260 duration[i] = timer.get_duration();
261 }
262
263 avrg_duration = duration.sum() / T;
264 min_duration = duration.minCoeff();
265 max_duration = duration.maxCoeff();
266 std::cout << " ShootingProblem.calcDiff [ms]: " << avrg_duration << " ("
267 << min_duration << "-" << max_duration << ")" << std::endl;
268 }
269