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