00001
00002
00003 #include "GaitGenerator.h"
00019 using namespace rats;
00020 #include <cstdio>
00021 #include <coil/stringutil.h>
00022
00023 #define eps_eq(a,b,epsilon) (std::fabs((a)-(b)) < (epsilon))
00024 #ifndef rad2deg
00025 #define rad2deg(rad) (rad * 180 / M_PI)
00026 #endif
00027 #ifndef deg2rad
00028 #define deg2rad(deg) (deg * M_PI / 180)
00029 #endif
00030
00031
00032
00033 template<class T> class ValueDifferenceChecker
00034 {
00035 T prev_value;
00036 double diff_thre, max_value_diff;
00037 bool is_small_diff, is_initialized;
00038 double calcDiff (T& value) const { return 0; };
00039 public:
00040 ValueDifferenceChecker (double _diff_thre) : diff_thre (_diff_thre), max_value_diff(0), is_small_diff(true), is_initialized(false)
00041 {
00042 };
00043 ~ValueDifferenceChecker () {};
00044 void checkValueDiff (T& value)
00045 {
00046
00047 if (!is_initialized) {
00048 prev_value = value;
00049 is_initialized = true;
00050 }
00051
00052 double diff = calcDiff(value);
00053 if (diff > max_value_diff) max_value_diff = diff;
00054 is_small_diff = (diff < diff_thre) && is_small_diff;
00055 prev_value = value;
00056 };
00057 double getMaxValue () const { return max_value_diff; };
00058 double getDiffThre () const { return diff_thre; };
00059 bool isSmallDiff () const { return is_small_diff; };
00060 };
00061
00062 template<> double ValueDifferenceChecker<hrp::Vector3>::calcDiff (hrp::Vector3& value) const
00063 {
00064 return (value - prev_value).norm();
00065 };
00066
00067 template<> double ValueDifferenceChecker< std::vector<hrp::Vector3> >::calcDiff (std::vector<hrp::Vector3>& value) const
00068 {
00069 double tmp = 0;
00070 for (size_t i = 0; i < value.size(); i++) {
00071 tmp += (value[i] - prev_value[i]).norm();
00072 }
00073 return tmp;
00074 };
00075
00076
00077
00078 class ValueErrorChecker
00079 {
00080 double error_thre, max_value_error;
00081 bool is_small_error;
00082 public:
00083 ValueErrorChecker (double _thre) : error_thre (_thre), max_value_error(0), is_small_error(true)
00084 {
00085 };
00086 ~ValueErrorChecker () {};
00087 void checkValueError (const hrp::Vector3& p0, const hrp::Vector3& p1, std::vector<size_t> neglect_index = std::vector<size_t>())
00088 {
00089 hrp::Vector3 errorv(p0-p1);
00090 for (size_t i = 0; i < neglect_index.size(); i++) errorv(neglect_index[i]) = 0.0;
00091 double error = errorv.norm();
00092 if (error > max_value_error) max_value_error = error;
00093 is_small_error = (error < error_thre) && is_small_error;
00094 };
00095 double getMaxValue () const { return max_value_error; };
00096 double getErrorThre () const { return error_thre; };
00097 bool isSmallError () const { return is_small_error; };
00098 };
00099
00100 class testGaitGenerator
00101 {
00102 protected:
00103 double dt;
00104 std::vector<hrp::Vector3> leg_pos;
00105 std::vector<std::string> all_limbs;
00106 hrp::Vector3 cog;
00107 gait_generator* gg;
00108 bool use_gnuplot, use_graph_append;
00109
00110 hrp::Vector3 prev_rfoot_pos, prev_lfoot_pos, prev_rfoot_rpy, prev_lfoot_rpy;
00111 hrp::Vector3 min_rfoot_pos, min_lfoot_pos, max_rfoot_pos, max_lfoot_pos;
00112 hrp::Vector3 prev_refzmp;
00113 coordinates prev_ssmc;
00114 std::vector<bool> prev_contact_states;
00115 std::vector<double> prev_swing_support_time;
00116 double min_toe_heel_dif_angle, max_toe_heel_dif_angle, min_zmp_offset_x, max_zmp_offset_x;
00117
00118 bool is_contact_states_swing_support_time_validity;
00119
00120 ValueDifferenceChecker< hrp::Vector3 > refzmp_diff_checker, cartzmp_diff_checker, cog_diff_checker, ssmcpos_diff_checker, ssmcrot_diff_checker, ssmcposvel_diff_checker, ssmcrotvel_diff_checker;
00121 ValueDifferenceChecker< std::vector<hrp::Vector3> > footpos_diff_checker, footrot_diff_checker, footposvel_diff_checker, footrotvel_diff_checker, zmpoffset_diff_checker;
00122
00123 ValueErrorChecker zmp_error_checker, cogzmp_error_checker;
00124
00125 std::vector<double> step_time_list, min_toe_heel_dif_angle_list, max_toe_heel_dif_angle_list, min_zmp_offset_x_list, max_zmp_offset_x_list;
00126 bool is_step_time_valid, is_toe_heel_dif_angle_valid, is_toe_heel_zmp_offset_x_valid;
00127
00128 std::string test_doc_string;
00129 std::string fname_cogzmp;
00130 FILE* fp_cogzmp;
00131 std::string fname_fpos;
00132 FILE* fp_fpos;
00133 std::string fname_frot;
00134 FILE* fp_frot;
00135 std::string fname_zoff;
00136 FILE* fp_zoff;
00137 std::string fname_fposvel;
00138 FILE* fp_fposvel;
00139 std::string fname_frotvel;
00140 FILE* fp_frotvel;
00141 std::string fname_thpos;
00142 FILE* fp_thpos;
00143 std::string fname_sstime;
00144 FILE* fp_sstime;
00145 std::string fname_ssmc;
00146 FILE* fp_ssmc;
00147 std::string fname_ssmcvel;
00148 FILE* fp_ssmcvel;
00149 private:
00151
00153
00154
00155 void plot_and_save (FILE* gp, const std::string graph_fname, const std::string plot_str)
00156 {
00157 fprintf(gp, "%s\n unset multiplot\n", plot_str.c_str());
00158 fprintf(gp, "set terminal postscript eps color\nset output '/tmp/%s.eps'\n", graph_fname.c_str());
00159 fprintf(gp, "%s\n unset multiplot\n", plot_str.c_str());
00160 fflush(gp);
00161 };
00162
00163
00164
00165 void proc_one_walking_motion (size_t i)
00166 {
00167
00168
00169
00170
00171
00172
00173
00174 fprintf(fp_cogzmp, "%f ", i * dt);
00175 for (size_t ii = 0; ii < 3; ii++) {
00176 fprintf(fp_cogzmp, "%f ", gg->get_refzmp()(ii));
00177 }
00178 hrp::Vector3 czmp = gg->get_cart_zmp();
00179 for (size_t ii = 0; ii < 3; ii++) {
00180 fprintf(fp_cogzmp, "%f ", czmp(ii));
00181 }
00182 for (size_t ii = 0; ii < 3; ii++) {
00183 double cogpos;
00184 if (ii==2) {
00185 coordinates tmpc;
00186 gg->get_swing_support_mid_coords(tmpc);
00187 cogpos = tmpc.pos(2)+gg->get_cog()(2);
00188 } else {
00189 cogpos = gg->get_cog()(ii);
00190 }
00191 fprintf(fp_cogzmp, "%f ", cogpos);
00192 }
00193 fprintf(fp_cogzmp, "\n");
00194 fflush(fp_cogzmp);
00195
00196 #define VEC1(s) std::vector<std::string> (1, s)
00197
00198
00199 fprintf(fp_fpos, "%f ", i * dt);
00200 hrp::Vector3 rfoot_pos = (gg->get_support_leg_names() == VEC1 ("rleg")) ? gg->get_support_leg_steps().front().worldcoords.pos : gg->get_swing_leg_steps().front().worldcoords.pos;
00201 for (size_t ii = 0; ii < 3; ii++) {
00202 fprintf(fp_fpos, "%f ", rfoot_pos(ii));
00203 min_rfoot_pos(ii) = std::min(min_rfoot_pos(ii), rfoot_pos(ii));
00204 max_rfoot_pos(ii) = std::max(max_rfoot_pos(ii), rfoot_pos(ii));
00205 }
00206 hrp::Vector3 lfoot_pos = (gg->get_support_leg_names() == VEC1("lleg")) ? gg->get_support_leg_steps().front().worldcoords.pos : gg->get_swing_leg_steps().front().worldcoords.pos;
00207 for (size_t ii = 0; ii < 3; ii++) {
00208 fprintf(fp_fpos, "%f ", lfoot_pos(ii));
00209 min_lfoot_pos(ii) = std::min(min_lfoot_pos(ii), lfoot_pos(ii));
00210 max_lfoot_pos(ii) = std::max(max_lfoot_pos(ii), lfoot_pos(ii));
00211 }
00212 fprintf(fp_fpos, "\n");
00213 fflush(fp_fpos);
00214
00215
00216 fprintf(fp_frot, "%f ", i * dt);
00217 hrp::Matrix33 rfoot_rot = (gg->get_support_leg_names() == VEC1("rleg")) ? gg->get_support_leg_steps().front().worldcoords.rot : gg->get_swing_leg_steps().front().worldcoords.rot;
00218 hrp::Vector3 rfoot_rpy = hrp::rpyFromRot(rfoot_rot);
00219 for (size_t ii = 0; ii < 3; ii++) {
00220 fprintf(fp_frot, "%f ", rad2deg(rfoot_rpy(ii)));
00221 }
00222 hrp::Matrix33 lfoot_rot = (gg->get_support_leg_names() == VEC1("lleg")) ? gg->get_support_leg_steps().front().worldcoords.rot : gg->get_swing_leg_steps().front().worldcoords.rot;
00223 hrp::Vector3 lfoot_rpy = hrp::rpyFromRot(lfoot_rot);
00224 for (size_t ii = 0; ii < 3; ii++) {
00225 fprintf(fp_frot, "%f ", rad2deg(lfoot_rpy(ii)));
00226 }
00227 fprintf(fp_frot, "\n");
00228 fflush(fp_frot);
00229
00230
00231 fprintf(fp_zoff, "%f ", i * dt);
00232 hrp::Vector3 rfoot_zmp_offset = (gg->get_support_leg_names() == VEC1("rleg")) ? gg->get_support_foot_zmp_offsets().front() : gg->get_swing_foot_zmp_offsets().front();
00233 for (size_t ii = 0; ii < 3; ii++) {
00234 fprintf(fp_zoff, "%f ", rfoot_zmp_offset(ii));
00235 }
00236 hrp::Vector3 lfoot_zmp_offset = (gg->get_support_leg_names() == VEC1("lleg")) ? gg->get_support_foot_zmp_offsets().front() : gg->get_swing_foot_zmp_offsets().front();
00237 for (size_t ii = 0; ii < 3; ii++) {
00238 fprintf(fp_zoff, "%f ", lfoot_zmp_offset(ii));
00239 }
00240 fprintf(fp_zoff, "\n");
00241 fflush(fp_zoff);
00242 double tmpzoff;
00243 if (gg->get_support_leg_names()[0] == "lleg") tmpzoff = rfoot_zmp_offset(0);
00244 else tmpzoff = lfoot_zmp_offset(0);
00245 min_zmp_offset_x = std::min(min_zmp_offset_x, tmpzoff);
00246 max_zmp_offset_x = std::max(max_zmp_offset_x, tmpzoff);
00247
00248 #undef VEC1
00249
00250
00251 fprintf(fp_fposvel, "%f ", i * dt);
00252 if ( i == 0 ) prev_rfoot_pos = rfoot_pos;
00253 hrp::Vector3 rfootpos_vel = (rfoot_pos - prev_rfoot_pos)/dt;
00254 for (size_t ii = 0; ii < 3; ii++) {
00255 fprintf(fp_fposvel, "%f ", rfootpos_vel(ii));
00256 }
00257 prev_rfoot_pos = rfoot_pos;
00258 if ( i == 0 ) prev_lfoot_pos = lfoot_pos;
00259 hrp::Vector3 lfootpos_vel = (lfoot_pos - prev_lfoot_pos)/dt;
00260 for (size_t ii = 0; ii < 3; ii++) {
00261 fprintf(fp_fposvel, "%f ", lfootpos_vel(ii));
00262 }
00263 prev_lfoot_pos = lfoot_pos;
00264 fprintf(fp_fposvel, "\n");
00265 fflush(fp_fposvel);
00266
00267
00268 fprintf(fp_frotvel, "%f ", i * dt);
00269 if ( i == 0 ) prev_rfoot_rpy = rfoot_rpy;
00270 hrp::Vector3 rfootrot_vel = (rfoot_rpy - prev_rfoot_rpy)/dt;
00271 for (size_t ii = 0; ii < 3; ii++) {
00272 fprintf(fp_frotvel, "%f ", rfootrot_vel(ii));
00273 }
00274 prev_rfoot_rpy = rfoot_rpy;
00275 if ( i == 0 ) prev_lfoot_rpy = lfoot_rpy;
00276 hrp::Vector3 lfootrot_vel = (lfoot_rpy - prev_lfoot_rpy)/dt;
00277 for (size_t ii = 0; ii < 3; ii++) {
00278 fprintf(fp_frotvel, "%f ", lfootrot_vel(ii));
00279 }
00280 prev_lfoot_rpy = lfoot_rpy;
00281 fprintf(fp_frotvel, "\n");
00282 fflush(fp_frotvel);
00283
00284
00285 fprintf(fp_thpos, "%f ", i * dt);
00286 hrp::Vector3 tmppos;
00287 tmppos = rfoot_pos+rfoot_rot*hrp::Vector3(gg->get_toe_pos_offset_x(), 0, 0);
00288 for (size_t ii = 0; ii < 3; ii++) {
00289 fprintf(fp_thpos, "%f ", tmppos(ii));
00290 min_rfoot_pos(ii) = std::min(min_rfoot_pos(ii), tmppos(ii));
00291 max_rfoot_pos(ii) = std::max(max_rfoot_pos(ii), tmppos(ii));
00292 }
00293 tmppos = lfoot_pos+lfoot_rot*hrp::Vector3(gg->get_toe_pos_offset_x(), 0, 0);
00294 for (size_t ii = 0; ii < 3; ii++) {
00295 fprintf(fp_thpos, "%f ", tmppos(ii));
00296 min_lfoot_pos(ii) = std::min(min_lfoot_pos(ii), tmppos(ii));
00297 max_lfoot_pos(ii) = std::max(max_lfoot_pos(ii), tmppos(ii));
00298 }
00299 tmppos = rfoot_pos+rfoot_rot*hrp::Vector3(gg->get_heel_pos_offset_x(), 0, 0);
00300 for (size_t ii = 0; ii < 3; ii++) {
00301 fprintf(fp_thpos, "%f ", tmppos(ii));
00302 min_rfoot_pos(ii) = std::min(min_rfoot_pos(ii), tmppos(ii));
00303 max_rfoot_pos(ii) = std::max(max_rfoot_pos(ii), tmppos(ii));
00304 }
00305 tmppos = lfoot_pos+lfoot_rot*hrp::Vector3(gg->get_heel_pos_offset_x(), 0, 0);
00306 for (size_t ii = 0; ii < 3; ii++) {
00307 fprintf(fp_thpos, "%f ", tmppos(ii));
00308 min_lfoot_pos(ii) = std::min(min_lfoot_pos(ii), tmppos(ii));
00309 max_lfoot_pos(ii) = std::max(max_lfoot_pos(ii), tmppos(ii));
00310 }
00311 fprintf(fp_thpos, "\n");
00312 fflush(fp_thpos);
00313
00314
00315 fprintf(fp_sstime, "%f ", i * dt);
00316 fprintf(fp_sstime, "%f %f ",
00317 gg->get_current_swing_time(RLEG),
00318 gg->get_current_swing_time(LLEG));
00319
00320 std::vector<leg_type> tmp_current_support_states = gg->get_current_support_states();
00321 bool rleg_contact_states = std::find_if(tmp_current_support_states.begin(), tmp_current_support_states.end(), boost::lambda::_1 == RLEG) != tmp_current_support_states.end();
00322 bool lleg_contact_states = std::find_if(tmp_current_support_states.begin(), tmp_current_support_states.end(), boost::lambda::_1 == LLEG) != tmp_current_support_states.end();
00323 fprintf(fp_sstime, "%d %d %f",
00324 (rleg_contact_states ? 1 : 0), (lleg_contact_states ? 1 : 0),
00325 0.8*gg->get_current_toe_heel_ratio()+0.1);
00326 fprintf(fp_sstime, "\n");
00327 fflush(fp_sstime);
00328
00329
00330 fprintf(fp_ssmc, "%f ", i * dt);
00331 coordinates tmp_ssmc;
00332 gg->get_swing_support_mid_coords(tmp_ssmc);
00333 for (size_t ii = 0; ii < 3; ii++) {
00334 fprintf(fp_ssmc, "%f ", tmp_ssmc.pos(ii));
00335 }
00336 hrp::Vector3 tmp_ssmcr = hrp::rpyFromRot(tmp_ssmc.rot);
00337 for (size_t ii = 0; ii < 3; ii++) {
00338 fprintf(fp_ssmc, "%f ", rad2deg(tmp_ssmcr(ii)));
00339 }
00340 fprintf(fp_ssmc, "\n");
00341 fflush(fp_ssmc);
00342
00343
00344 fprintf(fp_ssmcvel, "%f ", i * dt);
00345 if ( i == 0 ) prev_ssmc = tmp_ssmc;
00346 hrp::Vector3 tmp_ssmcpos_vel = (tmp_ssmc.pos - prev_ssmc.pos)/dt;
00347 for (size_t ii = 0; ii < 3; ii++) {
00348 fprintf(fp_ssmcvel, "%f ", tmp_ssmcpos_vel(ii));
00349 }
00350 hrp::Vector3 prev_ssmcr = hrp::rpyFromRot(prev_ssmc.rot);
00351 hrp::Vector3 tmp_ssmcrot_vel = (tmp_ssmcr - prev_ssmcr)/dt;
00352 for (size_t ii = 0; ii < 3; ii++) {
00353 fprintf(fp_ssmcvel, "%f ", tmp_ssmcrot_vel(ii));
00354 }
00355 fprintf(fp_ssmcvel, "\n");
00356 fflush(fp_ssmcvel);
00357 prev_ssmc = tmp_ssmc;
00358
00359
00360 double tmp_toe_heel_dif_angle = gg->get_toe_heel_dif_angle();
00361 min_toe_heel_dif_angle = std::min(min_toe_heel_dif_angle, tmp_toe_heel_dif_angle);
00362 max_toe_heel_dif_angle = std::max(max_toe_heel_dif_angle, tmp_toe_heel_dif_angle);
00363
00364
00365 if (gg->get_lcg_count() == 0) {
00366 step_time_list.push_back(gg->get_one_step_count()*dt);
00367 min_toe_heel_dif_angle_list.push_back(min_toe_heel_dif_angle);
00368 max_toe_heel_dif_angle_list.push_back(max_toe_heel_dif_angle);
00369 min_toe_heel_dif_angle = 1e10;
00370 max_toe_heel_dif_angle = -1e10;
00371 if ( !eps_eq(min_zmp_offset_x, gg->get_default_zmp_offsets()[0](0), 1e-5) ) min_zmp_offset_x_list.push_back(min_zmp_offset_x);
00372 else min_zmp_offset_x_list.push_back(0.0);
00373 if ( !eps_eq(max_zmp_offset_x, gg->get_default_zmp_offsets()[0](0), 1e-5) ) max_zmp_offset_x_list.push_back(max_zmp_offset_x);
00374 else max_zmp_offset_x_list.push_back(0.0);
00375 min_zmp_offset_x = 1e10;
00376 max_zmp_offset_x = -1e10;
00377 }
00378
00379
00380 {
00381
00382 zmp_error_checker.checkValueError(gg->get_cart_zmp(), gg->get_refzmp());
00383
00384
00385 hrp::Vector3 tmp(gg->get_refzmp());
00386 refzmp_diff_checker.checkValueDiff(tmp);
00387 tmp = gg->get_cart_zmp();
00388 cartzmp_diff_checker.checkValueDiff(tmp);
00389 tmp = gg->get_cog();
00390 cog_diff_checker.checkValueDiff(tmp);
00391
00392 std::vector<hrp::Vector3> tmpvec = boost::assign::list_of(rfoot_pos)(lfoot_pos);
00393 footpos_diff_checker.checkValueDiff(tmpvec);
00394 tmpvec = boost::assign::list_of(rfoot_rpy)(lfoot_rpy).convert_to_container < std::vector<hrp::Vector3> > ();
00395 footrot_diff_checker.checkValueDiff(tmpvec);
00396 tmpvec = boost::assign::list_of(rfootpos_vel)(lfootpos_vel).convert_to_container < std::vector<hrp::Vector3> > ();
00397 footposvel_diff_checker.checkValueDiff(tmpvec);
00398 tmpvec = boost::assign::list_of(rfootrot_vel)(lfootrot_vel).convert_to_container < std::vector<hrp::Vector3> > ();
00399 footrotvel_diff_checker.checkValueDiff(tmpvec);
00400
00401 ssmcpos_diff_checker.checkValueDiff(tmp_ssmc.pos);
00402 ssmcrot_diff_checker.checkValueDiff(tmp_ssmcr);
00403 ssmcposvel_diff_checker.checkValueDiff(tmp_ssmcpos_vel);
00404 ssmcrotvel_diff_checker.checkValueDiff(tmp_ssmcrot_vel);
00405
00406 tmpvec = boost::assign::list_of(rfoot_zmp_offset)(lfoot_zmp_offset).convert_to_container < std::vector<hrp::Vector3> > ();
00407 zmpoffset_diff_checker.checkValueDiff(tmpvec);
00408 }
00409
00410 is_contact_states_swing_support_time_validity = is_contact_states_swing_support_time_validity &&
00411 ((prev_contact_states[0] == rleg_contact_states) ? !eps_eq(prev_swing_support_time[0],dt,1e-5) : eps_eq(prev_swing_support_time[0],dt,1e-5)) &&
00412 ((prev_contact_states[1] == lleg_contact_states) ? !eps_eq(prev_swing_support_time[1],dt,1e-5) : eps_eq(prev_swing_support_time[1],dt,1e-5));
00413 prev_refzmp = gg->get_refzmp();
00414 prev_contact_states[0] = rleg_contact_states;
00415 prev_contact_states[1] = lleg_contact_states;
00416 prev_swing_support_time[0] = gg->get_current_swing_time(RLEG);
00417 prev_swing_support_time[1] = gg->get_current_swing_time(LLEG);
00418 };
00419
00420
00421 void plot_and_print_errorcheck ()
00422 {
00423
00424 if (use_gnuplot) {
00425 size_t gpsize = 12;
00426 FILE* gps[gpsize];
00427 for (size_t ii = 0; ii < gpsize;ii++) {
00428 gps[ii] = popen("gnuplot", "w");
00429 }
00430 {
00431 std::ostringstream oss("");
00432 std::string gtitle("COG_and_ZMP");
00433 size_t tmp_start = 2;
00434 oss << "set multiplot layout 3, 1 title '" << gtitle << "'" << std::endl;
00435 std::string titles[3] = {"X", "Y", "Z"};
00436 for (size_t ii = 0; ii < 3; ii++) {
00437 oss << "set xlabel 'Time [s]'" << std::endl;
00438 oss << "set ylabel '" << titles[ii] << "[m]'" << std::endl;
00439 oss << "plot "
00440 << "'" << fname_cogzmp << "' using 1:" << (tmp_start+ii) << " with lines title 'REFZMP',"
00441 << "'" << fname_cogzmp << "' using 1:" << (tmp_start+3+ii) << " with lines title 'CARTZMP',"
00442 << "'" << fname_cogzmp << "' using 1:" << (tmp_start+6+ii) << " with lines title 'COG'"
00443 << std::endl;
00444 }
00445 plot_and_save(gps[0], gtitle, oss.str());
00446 }
00447 {
00448 std::ostringstream oss("");
00449 std::string gtitle("Swing_support_pos");
00450 size_t tmp_start = 2;
00451 oss << "set multiplot layout 3, 1 title '" << gtitle << "'" << std::endl;
00452 std::string titles[3] = {"X", "Y", "Z"};
00453 for (size_t ii = 0; ii < 3; ii++) {
00454 oss << "set xlabel 'Time [s]'" << std::endl;
00455 oss << "set ylabel '" << titles[ii] << "[m]'" << std::endl;
00456 oss << "plot "
00457 << "'" << fname_fpos << "' using 1:" << (tmp_start+ii) << " with lines title 'rleg',"
00458 << "'" << fname_fpos << "' using 1:" << (tmp_start+3+ii) << " with lines title 'lleg'"
00459 << std::endl;
00460 }
00461 plot_and_save(gps[1], gtitle, oss.str());
00462 }
00463 {
00464 std::ostringstream oss("");
00465 std::string gtitle("Swing_support_rot");
00466 size_t tmp_start = 2;
00467 oss << "set multiplot layout 3, 1 title '" << gtitle << "'" << std::endl;
00468 std::string titles[3] = {"Roll", "Pitch", "Yaw"};
00469 for (size_t ii = 0; ii < 3; ii++) {
00470 oss << "set xlabel 'Time [s]'" << std::endl;
00471 oss << "set ylabel '" << titles[ii] << "[deg]'" << std::endl;
00472 oss << "plot "
00473 << "'" << fname_frot << "' using 1:" << (tmp_start+ii) << " with lines title 'rleg',"
00474 << "'" << fname_frot << "' using 1:" << (tmp_start+3+ii) << " with lines title 'lleg'"
00475 << std::endl;
00476 }
00477 plot_and_save(gps[2], gtitle, oss.str());
00478 }
00479 {
00480 std::ostringstream oss("");
00481 std::string gtitle("Swing_support_zmp_offset");
00482 size_t tmp_start = 2;
00483 oss << "set multiplot layout 3, 1 title '" << gtitle << "'" << std::endl;
00484 std::string titles[3] = {"X", "Y", "Z"};
00485 for (size_t ii = 0; ii < 3; ii++) {
00486 oss << "set xlabel 'Time [s]'" << std::endl;
00487 oss << "set ylabel '" << titles[ii] << "[m]'" << std::endl;
00488 oss << "plot "
00489 << "'" << fname_zoff << "' using 1:" << (tmp_start+ii) << " with lines title 'rleg',"
00490 << "'" << fname_zoff << "' using 1:" << (tmp_start+3+ii) << " with lines title 'lleg'"
00491 << std::endl;
00492 }
00493 plot_and_save(gps[3], gtitle, oss.str());
00494 }
00495 {
00496 std::ostringstream oss("");
00497 std::string gtitle("Swing_support_pos_vel");
00498 size_t tmp_start = 2;
00499 oss << "set multiplot layout 3, 1 title '" << gtitle << "'" << std::endl;
00500 std::string titles[3] = {"X", "Y", "Z"};
00501 for (size_t ii = 0; ii < 3; ii++) {
00502 oss << "set xlabel 'Time [s]'" << std::endl;
00503 oss << "set ylabel '" << titles[ii] << "[m/s]'" << std::endl;
00504 oss << "plot "
00505 << "'" << fname_fposvel << "' using 1:" << (tmp_start+ii) << " with lines title 'rleg',"
00506 << "'" << fname_fposvel << "' using 1:" << (tmp_start+3+ii) << " with lines title 'lleg'"
00507 << std::endl;
00508 }
00509 plot_and_save(gps[4], gtitle, oss.str());
00510 }
00511 {
00512 std::ostringstream oss("");
00513 std::string gtitle("Swing_support_rot_vel");
00514 size_t tmp_start = 2;
00515 oss << "set multiplot layout 3, 1 title '" << gtitle << "'" << std::endl;
00516 std::string titles[3] = {"Roll", "Pitch", "Yaw"};
00517 for (size_t ii = 0; ii < 3; ii++) {
00518 oss << "set xlabel 'Time [s]'" << std::endl;
00519 oss << "set ylabel '" << titles[ii] << "[deg/s]'" << std::endl;
00520 oss << "plot "
00521 << "'" << fname_frotvel << "' using 1:" << (tmp_start+ii) << " with lines title 'rleg',"
00522 << "'" << fname_frotvel << "' using 1:" << (tmp_start+3+ii) << " with lines title 'lleg'"
00523 << std::endl;
00524 }
00525 plot_and_save(gps[5], gtitle, oss.str());
00526 }
00527 {
00528 std::ostringstream oss("");
00529 std::string gtitle("Swing_support_pos_trajectory");
00530 double min_v[3], max_v[3], range[3];
00531 size_t tmp_thpos_start = 2;
00532 for (size_t ii = 0; ii < 3; ii++) {
00533 min_v[ii] = std::min(min_rfoot_pos(ii), min_lfoot_pos(ii));
00534 max_v[ii] = std::max(max_rfoot_pos(ii), max_lfoot_pos(ii));
00535 if (min_v[ii] == 0.0 && max_v[ii] == 0.0) {
00536 min_v[ii] = -0.1;
00537 max_v[ii] = 0.1;
00538 }
00539 range[ii] = max_v[ii] - min_v[ii];
00540 double mid = (max_v[ii]+min_v[ii])/2.0;
00541 min_v[ii] = mid + range[ii] * 1.05 * -0.5;
00542 max_v[ii] = mid + range[ii] * 1.05 * 0.5;
00543 }
00544 oss << "set multiplot layout 2, 1 title '" << gtitle << "'" << std::endl;
00545
00546 oss << "set size ratio " << range[2]/range[0] << std::endl;
00547 oss << "set xlabel 'X [m]'" << std::endl;
00548 oss << "set ylabel 'Z [m]'" << std::endl;
00549 oss << "plot "
00550 << "[" << min_v[0]<< ":" << max_v[0] << "]"
00551 << "[" << min_v[2] << ":" << max_v[2] << "]"
00552 << "'" << fname_fpos << "' using " << (2) << ":" << (2+2) << " with lines title 'rleg ee',"
00553 << "'" << fname_fpos << "' using " << (2+3) << ":" << (2+3+2) << " with lines title 'lleg ee',"
00554 << "'" << fname_thpos << "' using " << (tmp_thpos_start) << ":" << (tmp_thpos_start+2) << " with lines title 'rleg toe',"
00555 << "'" << fname_thpos << "' using " << (tmp_thpos_start+3) << ":" << (tmp_thpos_start+3+2) << " with lines title 'lleg toe',"
00556 << "'" << fname_thpos << "' using " << (tmp_thpos_start+3+3) << ":" << (tmp_thpos_start+3+3+2) << " with lines title 'rleg heel',"
00557 << "'" << fname_thpos << "' using " << (tmp_thpos_start+3+3+3) << ":" << (tmp_thpos_start+3+3+3+2) << " with lines title 'lleg heel'"
00558 << std::endl;
00559
00560 oss << "set size ratio " << range[2]/range[1] << std::endl;
00561 oss << "set xlabel 'Y [m]'" << std::endl;
00562 oss << "set ylabel 'Z [m]'" << std::endl;
00563 oss << "plot "
00564 << "[" << min_v[1]<< ":" << max_v[1] << "]"
00565 << "[" << min_v[2] << ":" << max_v[2] << "]"
00566 << "'" << fname_fpos << "' using " << (2+1) << ":" << (2+2) << " with lines title 'rleg ee',"
00567 << "'" << fname_fpos << "' using " << (2+3+1) << ":" << (2+3+2) << " with lines title 'lleg ee',"
00568 << "'" << fname_thpos << "' using " << (tmp_thpos_start+1) << ":" << (tmp_thpos_start+2) << " with lines title 'rleg toe',"
00569 << "'" << fname_thpos << "' using " << (tmp_thpos_start+3+1) << ":" << (tmp_thpos_start+3+2) << " with lines title 'lleg toe',"
00570 << "'" << fname_thpos << "' using " << (tmp_thpos_start+3+3+1) << ":" << (tmp_thpos_start+3+3+2) << " with lines title 'rleg heel',"
00571 << "'" << fname_thpos << "' using " << (tmp_thpos_start+3+3+3+1) << ":" << (tmp_thpos_start+3+3+3+2) << " with lines title 'lleg heel'"
00572 << std::endl;
00573 plot_and_save(gps[6], gtitle, oss.str());
00574 }
00575 {
00576 std::ostringstream oss("");
00577 std::string gtitle("Swing_support_remain_time");
00578 oss << "set multiplot layout 1, 1 title '" << gtitle << "'" << std::endl;
00579 oss << "set title 'Remain Time'" << std::endl;
00580 oss << "set xlabel 'Time [s]'" << std::endl;
00581 oss << "set ylabel 'Time [s]'" << std::endl;
00582 oss << "plot "
00583 << "'" << fname_sstime << "' using 1:" << 2 << " with lines title 'rleg remain time',"
00584 << "'" << fname_sstime << "' using 1:" << 3 << " with lines title 'lleg remain time',"
00585 << "'" << fname_sstime << "' using 1:" << 4 << " with lines title 'rleg contact states',"
00586 << "'" << fname_sstime << "' using 1:" << 5 << " with lines title 'lleg contact states',"
00587 << "'" << fname_sstime << "' using 1:" << 6 << " with lines title 'toe_heel_ratio*0.8+0.1'"
00588 << std::endl;
00589 plot_and_save(gps[7], gtitle, oss.str());
00590 }
00591 {
00592 std::ostringstream oss("");
00593 std::string gtitle("Swing_support_mid_coords_pos");
00594 size_t tmp_start = 2;
00595 oss << "set multiplot layout 3, 1 title '" << gtitle << "'" << std::endl;
00596 std::string titles[3] = {"X", "Y", "Z"};
00597 for (size_t ii = 0; ii < 3; ii++) {
00598 oss << "set xlabel 'Time [s]'" << std::endl;
00599 oss << "set ylabel 'Pos " << titles[ii] << "[m]'" << std::endl;
00600 oss << "plot "
00601 << "'" << fname_ssmc << "' using 1:" << (tmp_start+ii) << " with lines title ''"
00602 << std::endl;
00603 }
00604 plot_and_save(gps[8], gtitle, oss.str());
00605 }
00606 {
00607 std::ostringstream oss("");
00608 std::string gtitle("Swing_support_mid_coords_rot");
00609 size_t tmp_start = 2;
00610 oss << "set multiplot layout 3, 1 title '" << gtitle << "'" << std::endl;
00611 std::string titles[3] = {"Roll", "Pitch", "Yaw"};
00612 for (size_t ii = 0; ii < 3; ii++) {
00613 oss << "set xlabel 'Time [s]'" << std::endl;
00614 oss << "set ylabel 'Rot " << titles[ii] << "[deg]'" << std::endl;
00615 oss << "plot "
00616 << "'" << fname_ssmc << "' using 1:" << (tmp_start+ii+3) << " with lines title ''"
00617 << std::endl;
00618 }
00619 plot_and_save(gps[9], gtitle, oss.str());
00620 }
00621 {
00622 std::ostringstream oss("");
00623 std::string gtitle("Swing_support_mid_coords_pos_vel");
00624 size_t tmp_start = 2;
00625 oss << "set multiplot layout 3, 1 title '" << gtitle << "'" << std::endl;
00626 std::string titles[3] = {"X", "Y", "Z"};
00627 for (size_t ii = 0; ii < 3; ii++) {
00628 oss << "set xlabel 'Time [s]'" << std::endl;
00629 oss << "set ylabel 'PosVel " << titles[ii] << "[m/s]'" << std::endl;
00630 oss << "plot "
00631 << "'" << fname_ssmcvel << "' using 1:" << (tmp_start+ii) << " with lines title ''"
00632 << std::endl;
00633 }
00634 plot_and_save(gps[10], gtitle, oss.str());
00635 }
00636 {
00637 std::ostringstream oss("");
00638 std::string gtitle("Swing_support_mid_coords_rot_vel");
00639 size_t tmp_start = 2;
00640 oss << "set multiplot layout 3, 1 title '" << gtitle << "'" << std::endl;
00641 std::string titles[3] = {"Roll", "Pitch", "Yaw"};
00642 for (size_t ii = 0; ii < 3; ii++) {
00643 oss << "set xlabel 'Time [s]'" << std::endl;
00644 oss << "set ylabel 'RotVel " << titles[ii] << "[deg/s]'" << std::endl;
00645 oss << "plot "
00646 << "'" << fname_ssmcvel << "' using 1:" << (tmp_start+ii+3) << " with lines title ''"
00647 << std::endl;
00648 }
00649 plot_and_save(gps[11], gtitle, oss.str());
00650 }
00651
00652 if (use_graph_append) {
00653 int ret = 0;
00654 usleep(500000);
00655 ret = system("bash -c 'for f in /tmp/*.eps; do convert -density 250x250 $f ${f//eps}jpg; done'");
00656 ret = system("(cd /tmp; convert +append Swing_support_mid_coords_pos.jpg Swing_support_mid_coords_pos_vel.jpg Swing_support_mid_coords_rot.jpg Swing_support_mid_coords_rot_vel.jpg img1.jpg)");
00657 ret = system("(cd /tmp/; convert +append Swing_support_pos.jpg Swing_support_pos_vel.jpg Swing_support_rot.jpg Swing_support_rot_vel.jpg img2.jpg)");
00658 ret = system("(cd /tmp/; convert +append Swing_support_zmp_offset.jpg Swing_support_remain_time.jpg COG_and_ZMP.jpg Swing_support_pos_trajectory.jpg img3.jpg)");
00659 std::string tmpstr = test_doc_string.substr(0, test_doc_string.find(":"));
00660 for(size_t c = tmpstr.find_first_of(" "); c != std::string::npos; c = c = tmpstr.find_first_of(" ")){
00661 tmpstr.erase(c,1);
00662 }
00663 ret = system(std::string("(cd /tmp/; convert -append img1.jpg img2.jpg img3.jpg testGaitGeneratorResults_"+tmpstr+".jpg; rm -f /tmp/img[123].jpg /tmp/COG_and_ZMP.jpg /tmp/Swing_support*.jpg)").c_str());
00664 } else {
00665 double tmp;
00666 std::cin >> tmp;
00667 }
00668 for (size_t ii = 0; ii < gpsize; ii++) {
00669 fprintf(gps[ii], "exit\n");
00670 fflush(gps[ii]);
00671 pclose(gps[ii]);
00672 }
00673 }
00674 std::string tmpstr = test_doc_string.substr(0, test_doc_string.find(":"));
00675 for(size_t c = tmpstr.find_first_of(" "); c != std::string::npos; c = c = tmpstr.find_first_of(" ")){
00676 tmpstr.erase(c,1);
00677 }
00678 std::cerr << "Checking of " << tmpstr << " : all results = " << (check_all_results()?"true":"false") << std::endl;
00679 std::cerr << " ZMP error : " << (zmp_error_checker.isSmallError()?"true":"false") << ", max_error : " << zmp_error_checker.getMaxValue()*1e3 << "[mm], thre : " << zmp_error_checker.getErrorThre()*1e3 << "[mm]" << std::endl;
00680 std::cerr << " COGZMP error : " << (cogzmp_error_checker.isSmallError()?"true":"false") << ", max_error : " << cogzmp_error_checker.getMaxValue()*1e3 << "[mm], thre : " << cogzmp_error_checker.getErrorThre()*1e3 << "[mm]" << std::endl;
00681 std::cerr << " RefZMP diff : " << (refzmp_diff_checker.isSmallDiff()?"true":"false") << ", max_diff : " << refzmp_diff_checker.getMaxValue()*1e3 << "[mm], thre : " << refzmp_diff_checker.getDiffThre()*1e3 << "[mm]" << std::endl;
00682 std::cerr << " CartZMP diff : " << (cartzmp_diff_checker.isSmallDiff()?"true":"false") << ", max_diff : " << cartzmp_diff_checker.getMaxValue()*1e3 << "[mm], thre : " << cartzmp_diff_checker.getDiffThre()*1e3 << "[mm]" << std::endl;
00683 std::cerr << " COG diff : " << (cog_diff_checker.isSmallDiff()?"true":"false") << ", max_diff : " << cog_diff_checker.getMaxValue()*1e3 << "[mm], thre : " << cog_diff_checker.getDiffThre()*1e3 << "[mm]" <<std::endl;
00684 std::cerr << " FootPos diff : " << (footpos_diff_checker.isSmallDiff()?"true":"false") << ", max_diff : " << footpos_diff_checker.getMaxValue()*1e3 << "[mm], thre : " << footpos_diff_checker.getDiffThre()*1e3 << "[mm]" <<std::endl;
00685 std::cerr << " FootRot diff : " << (footrot_diff_checker.isSmallDiff()?"true":"false") << ", max_diff : " << rad2deg(footrot_diff_checker.getMaxValue()) << "[deg], thre : " << rad2deg(footrot_diff_checker.getDiffThre()) << "[deg]" <<std::endl;
00686 std::cerr << " FootPosVel diff : " << (footposvel_diff_checker.isSmallDiff()?"true":"false") << ", max_diff : " << footposvel_diff_checker.getMaxValue()*1e3 << "[mm/s], thre : " << footposvel_diff_checker.getDiffThre()*1e3 << "[mm/s]" <<std::endl;
00687 std::cerr << " FootRotVel diff : " << (footrotvel_diff_checker.isSmallDiff()?"true":"false") << ", max_diff : " << rad2deg(footrotvel_diff_checker.getMaxValue()) << "[deg/s], thre : " << rad2deg(footrotvel_diff_checker.getDiffThre()) << "[deg/s]" <<std::endl;
00688 std::cerr << " SwingSupportFootMidPos diff : " << (ssmcpos_diff_checker.isSmallDiff()?"true":"false") << ", max_diff : " << ssmcpos_diff_checker.getMaxValue()*1e3 << "[mm], thre : " << ssmcpos_diff_checker.getDiffThre()*1e3 << "[mm]" <<std::endl;
00689 std::cerr << " SwingSupportFootMidRot diff : " << (ssmcrot_diff_checker.isSmallDiff()?"true":"false") << ", max_diff : " << rad2deg(ssmcrot_diff_checker.getMaxValue()) << "[deg], thre : " << rad2deg(ssmcrot_diff_checker.getDiffThre()) << "[deg]" <<std::endl;
00690 std::cerr << " SwingSupportFootMidPosVel diff : " << (ssmcposvel_diff_checker.isSmallDiff()?"true":"false") << ", max_diff : " << ssmcposvel_diff_checker.getMaxValue()*1e3 << "[mm/s], thre : " << ssmcposvel_diff_checker.getDiffThre()*1e3 << "[mm/s]" <<std::endl;
00691 std::cerr << " SwingSupportFootMidRotVel diff : " << (ssmcrotvel_diff_checker.isSmallDiff()?"true":"false") << ", max_diff : " << rad2deg(ssmcrotvel_diff_checker.getMaxValue()) << "[deg/s], thre : " << rad2deg(ssmcrotvel_diff_checker.getDiffThre()) << "[deg/s]" <<std::endl;
00692 std::cerr << " ZMPOffset diff : " << (zmpoffset_diff_checker.isSmallDiff()?"true":"false") << ", max_diff : " << zmpoffset_diff_checker.getMaxValue()*1e3 << "[mm/s], thre : " << zmpoffset_diff_checker.getDiffThre()*1e3 << "[mm/s]" <<std::endl;
00693 std::cerr << " Contact states & swing support time validity : " << (is_contact_states_swing_support_time_validity?"true":"false") << std::endl;
00694 std::cerr << " Step time validity : " << (is_step_time_valid?"true":"false") << std::endl;
00695 std::cerr << " ToeHeel angle validity : " << (is_toe_heel_dif_angle_valid?"true":"false") << std::endl;
00696 std::cerr << " ToeHeel+ZMPoffset validity : " << (is_toe_heel_zmp_offset_x_valid?"true":"false") << std::endl;
00697 };
00698
00699 void check_start_values ()
00700 {
00701
00702 std::vector<size_t> neglect_index = boost::assign::list_of(2);
00703 cogzmp_error_checker.checkValueError(gg->get_cog(), gg->get_refzmp(), neglect_index);
00704 };
00705
00706 void check_end_values ()
00707 {
00708
00709 std::vector<size_t> neglect_index = boost::assign::list_of(2);
00710 cogzmp_error_checker.checkValueError(gg->get_cog(), gg->get_refzmp(), neglect_index);
00711
00712 std::vector< std::vector<step_node> > fsl;
00713 gg->get_footstep_nodes_list(fsl);
00714 is_step_time_valid = step_time_list.size() == fsl.size();
00715 if (is_step_time_valid) {
00716 for (size_t i = 0; i < step_time_list.size(); i++) {
00717 is_step_time_valid = eps_eq(step_time_list[i], fsl[i][0].step_time, 1e-5) && is_step_time_valid;
00718 }
00719 }
00720
00721 is_toe_heel_dif_angle_valid = (min_toe_heel_dif_angle_list.size() == fsl.size()) && (max_toe_heel_dif_angle_list.size() == fsl.size());
00722 if (is_toe_heel_dif_angle_valid) {
00723 if (gg->get_use_toe_heel_auto_set()) {
00724
00725 } else {
00726
00727 for (size_t i = 1; i < min_toe_heel_dif_angle_list.size(); i++) {
00728
00729
00730 is_toe_heel_dif_angle_valid = eps_eq(min_toe_heel_dif_angle_list[i], (-fsl[i][0].heel_angle), 1e-5)
00731 && eps_eq(max_toe_heel_dif_angle_list[i], fsl[i][0].toe_angle, 1e-5)
00732 && is_toe_heel_dif_angle_valid;
00733 }
00734 }
00735 }
00736
00737
00738 is_toe_heel_zmp_offset_x_valid = (min_zmp_offset_x_list.size() == fsl.size()) && (max_zmp_offset_x_list.size() == fsl.size());
00739 if (gg->get_use_toe_heel_transition()) {
00740 for (size_t i = 0; i < min_zmp_offset_x_list.size(); i++) {
00741
00742 bool heel_valid = true;
00743 if ( !eps_eq(min_toe_heel_dif_angle_list[i], 0.0, 1e-5) ) {
00744 heel_valid = eps_eq(min_zmp_offset_x_list[i], gg->get_heel_zmp_offset_x(), 1e-5);
00745 } else {
00746 heel_valid = !eps_eq(min_zmp_offset_x_list[i], gg->get_heel_zmp_offset_x(), 1e-5);
00747 }
00748 bool toe_valid = true;
00749 if ( !eps_eq(max_toe_heel_dif_angle_list[i], 0.0, 1e-5) ) {
00750 toe_valid = eps_eq(max_zmp_offset_x_list[i], gg->get_toe_zmp_offset_x(), 1e-5);
00751 } else {
00752 toe_valid = !eps_eq(max_zmp_offset_x_list[i], gg->get_toe_zmp_offset_x(), 1e-5);
00753 }
00754
00755 is_toe_heel_zmp_offset_x_valid = heel_valid && toe_valid && is_toe_heel_zmp_offset_x_valid;
00756 }
00757 } else {
00758
00759 }
00760 };
00761
00762
00763 void gen_and_plot_walk_pattern(const step_node& initial_support_leg_step, const step_node& initial_swing_leg_dst_step)
00764 {
00765 parse_params(false);
00766 gg->print_param();
00767 gg->initialize_gait_parameter(cog, boost::assign::list_of(initial_support_leg_step), boost::assign::list_of(initial_swing_leg_dst_step));
00768 while ( !gg->proc_one_tick() );
00769
00770
00771 check_start_values();
00772 size_t i = 0;
00773 while ( gg->proc_one_tick() ) {
00774 proc_one_walking_motion(i);
00775 i++;
00776 }
00777 check_end_values();
00778 plot_and_print_errorcheck ();
00779 };
00780
00781 void gen_and_plot_walk_pattern()
00782 {
00783 std::vector<std::string> tmp_string_vector = boost::assign::list_of("rleg");
00784 if (gg->get_footstep_front_leg_names() == tmp_string_vector) {
00785 step_node initial_support_leg_step = step_node(LLEG, coordinates(leg_pos[1]), 0, 0, 0, 0);
00786 step_node initial_swing_leg_dst_step = step_node(RLEG, coordinates(leg_pos[0]), 0, 0, 0, 0);
00787 gen_and_plot_walk_pattern(initial_support_leg_step, initial_swing_leg_dst_step);
00788 } else {
00789 step_node initial_support_leg_step = step_node(RLEG, coordinates(leg_pos[0]), 0, 0, 0, 0);
00790 step_node initial_swing_leg_dst_step = step_node(LLEG, coordinates(leg_pos[1]), 0, 0, 0, 0);
00791 gen_and_plot_walk_pattern(initial_support_leg_step, initial_swing_leg_dst_step);
00792 }
00793 }
00794
00795 public:
00796 std::vector<std::string> arg_strs;
00797 testGaitGenerator(double _dt) : dt(_dt), use_gnuplot(true), use_graph_append(false), is_contact_states_swing_support_time_validity(true),
00798 refzmp_diff_checker(20.0*1e-3), cartzmp_diff_checker(20.0*1e-3), cog_diff_checker(10.0*1e-3),
00799 ssmcpos_diff_checker(10.0*1e-3), ssmcrot_diff_checker(deg2rad(0.1)),
00800 ssmcposvel_diff_checker(10.0*1e-3), ssmcrotvel_diff_checker(deg2rad(1)),
00801 footpos_diff_checker(10.0*1e-3), footrot_diff_checker(deg2rad(1)),
00802 footposvel_diff_checker(40*1e-3), footrotvel_diff_checker(deg2rad(15)),
00803 zmpoffset_diff_checker(20.0*1e-3),
00804 zmp_error_checker(50*1e-3), cogzmp_error_checker(1.5*1e-3),
00805 min_rfoot_pos(1e10,1e10,1e10), min_lfoot_pos(1e10,1e10,1e10), max_rfoot_pos(-1e10,-1e10,-1e10), max_lfoot_pos(-1e10,-1e10,-1e10),
00806 min_toe_heel_dif_angle(1e10), max_toe_heel_dif_angle(-1e10), min_zmp_offset_x(1e10), max_zmp_offset_x(-1e10),
00807 prev_contact_states(2, true),
00808 prev_swing_support_time(2, 1e2),
00809 fname_cogzmp("/tmp/plot-cogzmp.dat"), fp_cogzmp(fopen(fname_cogzmp.c_str(), "w")),
00810 fname_fpos("/tmp/plot-fpos.dat"), fp_fpos(fopen(fname_fpos.c_str(), "w")),
00811 fname_frot("/tmp/plot-frot.dat"), fp_frot(fopen(fname_frot.c_str(), "w")),
00812 fname_zoff("/tmp/plot-zoff.dat"), fp_zoff(fopen(fname_zoff.c_str(), "w")),
00813 fname_fposvel("/tmp/plot-fposvel.dat"), fp_fposvel(fopen(fname_fposvel.c_str(), "w")),
00814 fname_frotvel("/tmp/plot-frotvel.dat"), fp_frotvel(fopen(fname_frotvel.c_str(), "w")),
00815 fname_thpos("/tmp/plot-thpos.dat"), fp_thpos(fopen(fname_thpos.c_str(), "w")),
00816 fname_sstime("/tmp/plot-sstime.dat"), fp_sstime(fopen(fname_sstime.c_str(), "w")),
00817 fname_ssmc("/tmp/plot-ssmc.dat"), fp_ssmc(fopen(fname_ssmc.c_str(), "w")),
00818 fname_ssmcvel("/tmp/plot-ssmcvel.dat"), fp_ssmcvel(fopen(fname_ssmcvel.c_str(), "w"))
00819 {};
00820
00821 virtual ~testGaitGenerator()
00822 {
00823 if (gg != NULL) {
00824 delete gg;
00825 gg = NULL;
00826 }
00827 fclose(fp_cogzmp);
00828 fclose(fp_fpos);
00829 fclose(fp_frot);
00830 fclose(fp_zoff);
00831 fclose(fp_fposvel);
00832 fclose(fp_frotvel);
00833 fclose(fp_thpos);
00834 fclose(fp_sstime);
00835 fclose(fp_ssmc);
00836 fclose(fp_ssmcvel);
00837 };
00838
00839 void test0 ()
00840 {
00841 test_doc_string = "test0 : Set foot steps";
00842
00843 parse_params();
00844 std::vector< std::vector<step_node> > fnsl;
00845 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(0, 0, 0)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
00846 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(0, 0, 0)+leg_pos[1])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
00847 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(100*1e-3, 0, 0)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
00848 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(200*1e-3, 0, 0)+leg_pos[1])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
00849 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(200*1e-3, 0, 0)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
00850 gg->set_foot_steps_list(fnsl);
00851 gen_and_plot_walk_pattern();
00852 };
00853
00854 void test1 ()
00855 {
00856 test_doc_string = "test1 : Go pos x,y,th combination";
00857
00858 parse_params();
00859 gg->clear_footstep_nodes_list();
00860 coordinates start_ref_coords;
00861 mid_coords(start_ref_coords, 0.5, coordinates(leg_pos[0]), coordinates(leg_pos[1]));
00862 gg->go_pos_param_2_footstep_nodes_list(200*1e-3, 100*1e-3, 20, boost::assign::list_of(coordinates(leg_pos[0])), start_ref_coords, boost::assign::list_of(RLEG));
00863 gen_and_plot_walk_pattern();
00864 };
00865
00866 void test2 ()
00867 {
00868 test_doc_string = "test2 : Go pos x";
00869
00870 parse_params();
00871 gg->clear_footstep_nodes_list();
00872 coordinates start_ref_coords;
00873 mid_coords(start_ref_coords, 0.5, coordinates(leg_pos[1]), coordinates(leg_pos[0]));
00874 gg->go_pos_param_2_footstep_nodes_list(300*1e-3, 0, 0, boost::assign::list_of(coordinates(leg_pos[1])), start_ref_coords, boost::assign::list_of(LLEG));
00875 gen_and_plot_walk_pattern();
00876 };
00877
00878 void test3 ()
00879 {
00880 test_doc_string = "test3 : Go pos y";
00881
00882 parse_params();
00883 gg->clear_footstep_nodes_list();
00884 coordinates start_ref_coords;
00885 mid_coords(start_ref_coords, 0.5, coordinates(leg_pos[0]), coordinates(leg_pos[1]));
00886 gg->go_pos_param_2_footstep_nodes_list(0, 150*1e-3, 0, boost::assign::list_of(coordinates(leg_pos[0])), start_ref_coords, boost::assign::list_of(RLEG));
00887 gen_and_plot_walk_pattern();
00888 };
00889
00890 void test4 ()
00891 {
00892 test_doc_string = "test4 : Go pos th";
00893
00894 parse_params();
00895 gg->clear_footstep_nodes_list();
00896 coordinates start_ref_coords;
00897 mid_coords(start_ref_coords, 0.5, coordinates(leg_pos[1]), coordinates(leg_pos[0]));
00898 gg->go_pos_param_2_footstep_nodes_list(0, 0, 30, boost::assign::list_of(coordinates(leg_pos[1])), start_ref_coords, boost::assign::list_of(LLEG));
00899 gen_and_plot_walk_pattern();
00900 };
00901
00902 void test5 ()
00903 {
00904 test_doc_string = "test5 : Set foot steps with Z change";
00905
00906 parse_params();
00907 gg->set_default_orbit_type(CYCLOIDDELAY);
00908 std::vector< std::vector<step_node> > fnsl;
00909 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(0, 0, 0)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
00910 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(0, 0, 0)+leg_pos[1])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
00911 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(100*1e-3, 0, 100*1e-3)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
00912 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(200*1e-3, 0, 200*1e-3)+leg_pos[1])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
00913 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(300*1e-3, 0, 300*1e-3)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
00914 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(300*1e-3, 0, 300*1e-3)+leg_pos[1])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
00915 gg->set_foot_steps_list(fnsl);
00916 gen_and_plot_walk_pattern();
00917 };
00918
00919 void test6 ()
00920 {
00921 test_doc_string = "test6 : Go single step";
00922 parse_params();
00923 gg->clear_footstep_nodes_list();
00924 std::vector< std::vector<step_node> > fnsl;
00925 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(0, 0, 0)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
00926 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(100*1e-3, 75*1e-3, 0)+leg_pos[1]), hrp::rotFromRpy(hrp::Vector3(deg2rad(5), deg2rad(-20), deg2rad(10)))),
00927 gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
00928 gg->set_foot_steps_list(fnsl);
00929 gen_and_plot_walk_pattern();
00930 };
00931
00932 void test7 ()
00933 {
00934 test_doc_string = "test7 : Toe heel walk";
00935
00936 parse_params();
00937 std::vector<hrp::Vector3> dzo;
00938 dzo.push_back(hrp::Vector3(20*1e-3,-30*1e-3,0));
00939 dzo.push_back(hrp::Vector3(20*1e-3,30*1e-3,0));
00940 gg->set_default_zmp_offsets(dzo);
00941 gg->set_toe_zmp_offset_x(137*1e-3);
00942 gg->set_heel_zmp_offset_x(-105*1e-3);
00943 gg->set_toe_pos_offset_x(137*1e-3);
00944 gg->set_heel_pos_offset_x(-105*1e-3);
00945 gg->set_stride_parameters(0.2,0.1,20,0.2,0.1*0.5,20*0.5);
00946 gg->set_use_toe_heel_auto_set(true);
00947 gg->set_toe_angle(30);
00948 gg->set_heel_angle(10);
00949
00950 gg->set_use_toe_heel_transition(true);
00951 gg->clear_footstep_nodes_list();
00952 coordinates start_ref_coords;
00953 mid_coords(start_ref_coords, 0.5, coordinates(leg_pos[1]), coordinates(leg_pos[0]));
00954 gg->go_pos_param_2_footstep_nodes_list(400*1e-3, 0, 0, boost::assign::list_of(coordinates(leg_pos[1])), start_ref_coords, boost::assign::list_of(LLEG));
00955 gen_and_plot_walk_pattern();
00956 };
00957
00958 void test8 ()
00959 {
00960 test_doc_string = "test8 : Toe heel walk on slope";
00961
00962 parse_params();
00963 std::vector<hrp::Vector3> dzo;
00964 dzo.push_back(hrp::Vector3(20*1e-3,-30*1e-3,0));
00965 dzo.push_back(hrp::Vector3(20*1e-3,30*1e-3,0));
00966 gg->set_default_zmp_offsets(dzo);
00967 gg->set_toe_zmp_offset_x(137*1e-3);
00968 gg->set_heel_zmp_offset_x(-105*1e-3);
00969 gg->set_toe_pos_offset_x(137*1e-3);
00970 gg->set_heel_pos_offset_x(-105*1e-3);
00971 gg->set_toe_angle(30);
00972 gg->set_heel_angle(10);
00973
00974 gg->set_use_toe_heel_transition(true);
00975 gg->clear_footstep_nodes_list();
00976 hrp::Matrix33 initial_foot_mid_rot = Eigen::AngleAxis<double>(M_PI/2, hrp::Vector3::UnitZ()).toRotationMatrix();
00977
00978 coordinates start_ref_coords;
00979 mid_coords(start_ref_coords, 0.5, coordinates(initial_foot_mid_rot*leg_pos[1], initial_foot_mid_rot), coordinates(initial_foot_mid_rot*leg_pos[0], initial_foot_mid_rot));
00980 gg->go_pos_param_2_footstep_nodes_list(100*1e-3, 0, 0, boost::assign::list_of(coordinates(initial_foot_mid_rot*leg_pos[1], initial_foot_mid_rot)), start_ref_coords, boost::assign::list_of(LLEG));
00981
00982 std::vector<std::string> tmp_string_vector = boost::assign::list_of("rleg");
00983 if (gg->get_footstep_front_leg_names() == tmp_string_vector) {
00984 step_node initial_support_leg_step = step_node(LLEG, coordinates(hrp::Vector3(initial_foot_mid_rot * leg_pos[1]), initial_foot_mid_rot), 0, 0, 0, 0);
00985 step_node initial_swing_leg_dst_step = step_node(RLEG, coordinates(hrp::Vector3(initial_foot_mid_rot * leg_pos[0]), initial_foot_mid_rot), 0, 0, 0, 0);
00986 gen_and_plot_walk_pattern(initial_support_leg_step, initial_swing_leg_dst_step);
00987 } else {
00988 step_node initial_support_leg_step = step_node(RLEG, coordinates(hrp::Vector3(initial_foot_mid_rot * leg_pos[0]), initial_foot_mid_rot), 0, 0, 0, 0);
00989 step_node initial_swing_leg_dst_step = step_node(LLEG, coordinates(hrp::Vector3(initial_foot_mid_rot * leg_pos[1]), initial_foot_mid_rot), 0, 0, 0, 0);
00990 gen_and_plot_walk_pattern(initial_support_leg_step, initial_swing_leg_dst_step);
00991 }
00992 };
00993
00994 void test9 ()
00995 {
00996 test_doc_string = "test9 : Stair walk";
00997
00998 parse_params();
00999 gg->clear_footstep_nodes_list();
01000 gg->set_default_orbit_type(STAIR);
01001 gg->set_swing_trajectory_delay_time_offset (0.2);
01002 std::vector< std::vector<step_node> > fnsl;
01003 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(0, 0, 0)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01004 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(0, 0, 0)+leg_pos[1])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01005 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(250*1e-3, 0, 200*1e-3)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01006 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(250*1e-3, 0, 200*1e-3)+leg_pos[1])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01007 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(500*1e-3, 0, 400*1e-3)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01008 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(500*1e-3, 0, 400*1e-3)+leg_pos[1])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01009 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(750*1e-3, 0, 600*1e-3)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01010 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(750*1e-3, 0, 600*1e-3)+leg_pos[1])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01011 gg->set_foot_steps_list(fnsl);
01012 gen_and_plot_walk_pattern();
01013 };
01014
01015 void test10 ()
01016 {
01017 test_doc_string = "test10 : Stair walk + toe heel contact";
01018
01019 parse_params();
01020 gg->clear_footstep_nodes_list();
01021 gg->set_default_orbit_type(STAIR);
01022 gg->set_swing_trajectory_delay_time_offset (0.2);
01023 gg->set_toe_zmp_offset_x(137*1e-3);
01024 gg->set_heel_zmp_offset_x(-105*1e-3);
01025 gg->set_toe_pos_offset_x(137*1e-3);
01026 gg->set_heel_pos_offset_x(-105*1e-3);
01027 gg->set_toe_angle(20);
01028 gg->set_heel_angle(5);
01029 gg->set_default_step_time(1.5);
01030 gg->set_default_double_support_ratio_before(0.1);
01031 gg->set_default_double_support_ratio_after(0.1);
01032 double ratio[7] = {0.02, 0.28, 0.2, 0.0, 0.2, 0.25, 0.05};
01033 std::vector<double> ratio2(ratio, ratio+gg->get_NUM_TH_PHASES());
01034 gg->set_toe_heel_phase_ratio(ratio2);
01035 std::vector< std::vector<step_node> > fnsl;
01036 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(0, 0, 0)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01037 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(0, 0, 0)+leg_pos[1])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01038 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(250*1e-3, 0, 200*1e-3)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01039 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(250*1e-3, 0, 200*1e-3)+leg_pos[1])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01040 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(500*1e-3, 0, 400*1e-3)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01041 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(500*1e-3, 0, 400*1e-3)+leg_pos[1])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01042 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(750*1e-3, 0, 600*1e-3)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01043 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(750*1e-3, 0, 600*1e-3)+leg_pos[1])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01044 gg->set_foot_steps_list(fnsl);
01045 gen_and_plot_walk_pattern();
01046 };
01047
01048 void test11 ()
01049 {
01050 test_doc_string = "test11 : Foot rot change";
01051
01052 parse_params();
01053 hrp::Matrix33 tmpr;
01054 std::vector< std::vector<step_node> > fnsl;
01055 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(0, 0, 0)+leg_pos[1])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01056 tmpr = hrp::rotFromRpy(5*M_PI/180.0, 15*M_PI/180.0, 0);
01057 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(250*1e-3, 0, 0*1e-3)+leg_pos[0]), tmpr), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01058 tmpr = hrp::rotFromRpy(-5*M_PI/180.0, -15*M_PI/180.0, 0);
01059 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(250*1e-3, 0, 0*1e-3)+leg_pos[1]), tmpr), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01060 gg->set_foot_steps_list(fnsl);
01061 gen_and_plot_walk_pattern();
01062 };
01063
01064 void test12 ()
01065 {
01066 test_doc_string = "test12 : Change step param in set foot steps";
01067
01068 parse_params();
01069 std::vector< std::vector<step_node> > fnsl;
01070 gg->set_default_step_time(4.0);
01071 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(0, 0, 0)+leg_pos[0])), gg->get_default_step_height(), 1.0, 0, 0)));
01072 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(0, 0, 0)+leg_pos[1])), gg->get_default_step_height(), 2.0, 0, 0)));
01073 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(100*1e-3, 0, 0)+leg_pos[0])), gg->get_default_step_height()*2, 1.5, 0, 0)));
01074 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(200*1e-3, 0, 0)+leg_pos[1])), gg->get_default_step_height(), 2.5, 0, 0)));
01075 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(300*1e-3, 0, 0)+leg_pos[0])), gg->get_default_step_height(), 1.0, 20, 5)));
01076 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(300*1e-3, 0, 0)+leg_pos[1])), gg->get_default_step_height(), 2.0, 0, 0)));
01077 gg->set_foot_steps_list(fnsl);
01078 gen_and_plot_walk_pattern();
01079 };
01080
01081 void test13 ()
01082 {
01083 test_doc_string = "test13 : Arbitrary leg switching";
01084
01085 parse_params();
01086 std::vector< std::vector<step_node> > fnsl;
01087 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(0, 0, 0)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), 0, 0)));
01088 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(0, 0, 0)+leg_pos[1])), gg->get_default_step_height(), gg->get_default_step_time(), 0, 0)));
01089 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(100*1e-3, 0, 0)+leg_pos[1])), gg->get_default_step_height(), gg->get_default_step_time(), 0, 0)));
01090 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(100*1e-3, 0, 0)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), 0, 0)));
01091 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(200*1e-3, 0, 0)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), 0, 0)));
01092 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(200*1e-3, 0, 0)+leg_pos[1])), gg->get_default_step_height(), gg->get_default_step_time(), 0, 0)));
01093 gg->set_foot_steps_list(fnsl);
01094 gen_and_plot_walk_pattern();
01095 };
01096
01097 void test14 ()
01098 {
01099 test_doc_string = "test14 : kick walk";
01100
01101 parse_params();
01102 gg->clear_footstep_nodes_list();
01103 gg->set_default_orbit_type(CYCLOIDDELAYKICK);
01104 coordinates start_ref_coords;
01105 mid_coords(start_ref_coords, 0.5, coordinates(leg_pos[1]), coordinates(leg_pos[0]));
01106 gg->go_pos_param_2_footstep_nodes_list(300*1e-3, 0, 0, boost::assign::list_of(coordinates(leg_pos[1])), start_ref_coords, boost::assign::list_of(LLEG));
01107 gen_and_plot_walk_pattern();
01108 };
01109
01110 void test15 ()
01111 {
01112 test_doc_string = "test15 : Stair walk down";
01113
01114 parse_params();
01115 gg->clear_footstep_nodes_list();
01116 gg->set_default_orbit_type(STAIR);
01117 gg->set_swing_trajectory_delay_time_offset (0.2);
01118 std::vector< std::vector<step_node> > fnsl;
01119 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(0, 0, 0)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01120 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(0, 0, 0)+leg_pos[1])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01121 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(250*1e-3, 0, -200*1e-3)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01122 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(250*1e-3, 0, -200*1e-3)+leg_pos[1])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01123 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(500*1e-3, 0, -400*1e-3)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01124 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(500*1e-3, 0, -400*1e-3)+leg_pos[1])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01125 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(750*1e-3, 0, -600*1e-3)+leg_pos[0])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01126 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(750*1e-3, 0, -600*1e-3)+leg_pos[1])), gg->get_default_step_height(), gg->get_default_step_time(), gg->get_toe_angle(), gg->get_heel_angle())));
01127 gg->set_foot_steps_list(fnsl);
01128 gen_and_plot_walk_pattern();
01129 };
01130
01131 void test16 ()
01132 {
01133 test_doc_string = "test16 : Set foot steps with param (toe heel contact)";
01134
01135 parse_params();
01136 gg->clear_footstep_nodes_list();
01137 std::vector<hrp::Vector3> dzo;
01138 dzo.push_back(hrp::Vector3(20*1e-3,-30*1e-3,0));
01139 dzo.push_back(hrp::Vector3(20*1e-3,30*1e-3,0));
01140 gg->set_default_zmp_offsets(dzo);
01141 gg->set_toe_zmp_offset_x(137*1e-3);
01142 gg->set_heel_zmp_offset_x(-105*1e-3);
01143 gg->set_toe_pos_offset_x(137*1e-3);
01144 gg->set_heel_pos_offset_x(-105*1e-3);
01145 gg->set_toe_angle(20);
01146 gg->set_heel_angle(5);
01147 gg->set_default_step_time(2);
01148 gg->set_default_double_support_ratio_before(0.1);
01149 gg->set_default_double_support_ratio_after(0.1);
01150 gg->set_use_toe_heel_auto_set(true);
01151 gg->set_use_toe_heel_transition(true);
01152
01153 double ratio[7] = {0.07, 0.20, 0.2, 0.0, 0.2, 0.25, 0.08};
01154 std::vector<double> ratio2(ratio, ratio+gg->get_NUM_TH_PHASES());
01155 gg->set_toe_heel_phase_ratio(ratio2);
01156 std::vector< std::vector<step_node> > fnsl;
01157 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(0, 0, 0)+leg_pos[0])), gg->get_default_step_height()*0.5, gg->get_default_step_time()*0.5, gg->get_toe_angle()*0.5, gg->get_heel_angle()*0.5)));
01158 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(100*1e-3, 0, 0)+leg_pos[1])), gg->get_default_step_height()*2.0, gg->get_default_step_time()*2.0, gg->get_toe_angle()*2.0, gg->get_heel_angle()*2.0)));
01159 fnsl.push_back(boost::assign::list_of(step_node("rleg", coordinates(hrp::Vector3(hrp::Vector3(400*1e-3, 0, 0)+leg_pos[0])), gg->get_default_step_height()*0.5, gg->get_default_step_time()*0.5, gg->get_toe_angle()*0.5, gg->get_heel_angle()*0.5)));
01160 fnsl.push_back(boost::assign::list_of(step_node("lleg", coordinates(hrp::Vector3(hrp::Vector3(400*1e-3, 0, 0)+leg_pos[1])), gg->get_default_step_height()*2.0, gg->get_default_step_time()*2.0, gg->get_toe_angle()*2.0, gg->get_heel_angle()*2.0)));
01161 gg->set_foot_steps_list(fnsl);
01162 gen_and_plot_walk_pattern();
01163 };
01164
01165 void test17 ()
01166 {
01167 test_doc_string = "test17 : Test goVelocity (dx = 0.1, dy = 0.05, dth = 10.0)";
01168
01169 parse_params();
01170 gg->clear_footstep_nodes_list();
01171 gg->print_param();
01172 step_node initial_support_leg_step = step_node(LLEG, coordinates(leg_pos[1]), 0, 0, 0, 0);
01173 step_node initial_swing_leg_dst_step = step_node(RLEG, coordinates(leg_pos[0]), 0, 0, 0, 0);
01174 coordinates fm_coords;
01175 mid_coords(fm_coords, 0.5, initial_swing_leg_dst_step.worldcoords, initial_support_leg_step.worldcoords);
01176 gg->initialize_velocity_mode(fm_coords, 0.1, 0.05, 10.0, boost::assign::list_of(RLEG));
01177 gg->initialize_gait_parameter(cog, boost::assign::list_of(initial_support_leg_step), boost::assign::list_of(initial_swing_leg_dst_step));
01178 while ( !gg->proc_one_tick() );
01179
01180 check_start_values();
01181 size_t i = 0;
01182 while ( gg->proc_one_tick() ) {
01183 proc_one_walking_motion(i);
01184 i++;
01185 if ( i > static_cast<size_t>(gg->get_default_step_time()/dt) && gg->get_overwrite_check_timing() ) {
01186 gg->finalize_velocity_mode();
01187 }
01188 }
01189 check_end_values();
01190 plot_and_print_errorcheck ();
01191 };
01192
01193 void test18 ()
01194 {
01195 test_doc_string = "test18 : Test goVelocity with changing velocity (translation and rotation)";
01196
01197 parse_params();
01198 gg->clear_footstep_nodes_list();
01199 gg->set_overwritable_footstep_index_offset(0);
01200 gg->set_default_orbit_type(CYCLOIDDELAY);
01201 gg->print_param();
01202 step_node initial_support_leg_step = step_node(LLEG, coordinates(leg_pos[1]), 0, 0, 0, 0);
01203 step_node initial_swing_leg_dst_step = step_node(RLEG, coordinates(leg_pos[0]), 0, 0, 0, 0);
01204 coordinates fm_coords;
01205 mid_coords(fm_coords, 0.5, initial_swing_leg_dst_step.worldcoords, initial_support_leg_step.worldcoords);
01206 gg->initialize_velocity_mode(fm_coords, 0, 0, 0, boost::assign::list_of(RLEG));
01207 gg->initialize_gait_parameter(cog, boost::assign::list_of(initial_support_leg_step), boost::assign::list_of(initial_swing_leg_dst_step));
01208 while ( !gg->proc_one_tick() );
01209
01210 check_start_values();
01211 size_t i = 0;
01212 while ( gg->proc_one_tick() ) {
01213 proc_one_walking_motion(i);
01214 i++;
01215 if ( i > static_cast<size_t>(gg->get_default_step_time()/dt)*5 && gg->get_overwrite_check_timing() ) {
01216 gg->finalize_velocity_mode();
01217 } else if ( i > static_cast<size_t>(gg->get_default_step_time()/dt)*4 && gg->get_overwrite_check_timing() ) {
01218 gg->set_velocity_param(0, 0, 0);
01219 } else if ( i > static_cast<size_t>(gg->get_default_step_time()/dt)*3 && gg->get_overwrite_check_timing() ) {
01220 gg->set_velocity_param(0, 0, 10);
01221 } else if ( i > static_cast<size_t>(gg->get_default_step_time()/dt)*2 && gg->get_overwrite_check_timing() ) {
01222 gg->set_velocity_param(0, 0, 0);
01223 } else if ( i > static_cast<size_t>(gg->get_default_step_time()/dt) && gg->get_overwrite_check_timing() ) {
01224 gg->set_velocity_param(0.1, 0.05, 0);
01225 }
01226 }
01227 check_end_values();
01228 plot_and_print_errorcheck ();
01229 };
01230
01231 void test19 ()
01232 {
01233 test_doc_string = "test19 : Change stride parameter (translate)";
01234
01235 parse_params();
01236 std::vector<hrp::Vector3> dzo;
01237 dzo.push_back(hrp::Vector3(20*1e-3,-30*1e-3,0));
01238 dzo.push_back(hrp::Vector3(20*1e-3,30*1e-3,0));
01239 gg->set_default_zmp_offsets(dzo);
01240 gg->set_stride_parameters(0.25,0.15,25,0.25,0.1,10);
01241 gg->clear_footstep_nodes_list();
01242 coordinates start_ref_coords;
01243 mid_coords(start_ref_coords, 0.5, coordinates(leg_pos[1]), coordinates(leg_pos[0]));
01244 gg->go_pos_param_2_footstep_nodes_list(600*1e-3, -300*1e-3, 0, boost::assign::list_of(coordinates(leg_pos[1])), start_ref_coords, boost::assign::list_of(LLEG));
01245 gen_and_plot_walk_pattern();
01246 };
01247
01248 void test20 ()
01249 {
01250 test_doc_string = "test20 : Change stride parameter (translate+rotate)";
01251
01252 parse_params();
01253 std::vector<hrp::Vector3> dzo;
01254 dzo.push_back(hrp::Vector3(20*1e-3,-30*1e-3,0));
01255 dzo.push_back(hrp::Vector3(20*1e-3,30*1e-3,0));
01256 gg->set_default_zmp_offsets(dzo);
01257 gg->set_stride_parameters(0.25,0.15,25,0.25,0.1,10);
01258 gg->clear_footstep_nodes_list();
01259 coordinates start_ref_coords;
01260 mid_coords(start_ref_coords, 0.5, coordinates(leg_pos[1]), coordinates(leg_pos[0]));
01261 gg->go_pos_param_2_footstep_nodes_list(400*1e-3, -200*1e-3, -55, boost::assign::list_of(coordinates(leg_pos[1])), start_ref_coords, boost::assign::list_of(LLEG));
01262 gen_and_plot_walk_pattern();
01263 };
01264
01265 void parse_params (bool is_print_doc_setring = true)
01266 {
01267 if (is_print_doc_setring) std::cerr << test_doc_string << std::endl;
01268 for (unsigned int i = 0; i < arg_strs.size(); ++ i) {
01269 if ( arg_strs[i]== "--default-step-time" ) {
01270 if (++i < arg_strs.size()) gg->set_default_step_time(atof(arg_strs[i].c_str()));
01271 } else if ( arg_strs[i]== "--default-step-height" ) {
01272 if (++i < arg_strs.size()) gg->set_default_step_height(atof(arg_strs[i].c_str()));
01273 } else if ( arg_strs[i]== "--default-double-support-ratio-before" ) {
01274 if (++i < arg_strs.size()) gg->set_default_double_support_ratio_before(atof(arg_strs[i].c_str()));
01275 } else if ( arg_strs[i]== "--default-double-support-ratio-after" ) {
01276 if (++i < arg_strs.size()) gg->set_default_double_support_ratio_after(atof(arg_strs[i].c_str()));
01277 } else if ( arg_strs[i]== "--default-orbit-type" ) {
01278 if (++i < arg_strs.size()) {
01279 if (arg_strs[i] == "SHUFFLING") {
01280 gg->set_default_orbit_type(SHUFFLING);
01281 } else if (arg_strs[i] == "CYCLOID") {
01282 gg->set_default_orbit_type(CYCLOID);
01283 } else if (arg_strs[i] == "RECTANGLE") {
01284 gg->set_default_orbit_type(RECTANGLE);
01285 } else if (arg_strs[i] == "STAIR") {
01286 gg->set_default_orbit_type(STAIR);
01287 } else if (arg_strs[i] == "CYCLOIDDELAY") {
01288 gg->set_default_orbit_type(CYCLOIDDELAY);
01289 } else if (arg_strs[i] == "CYCLOIDDELAYKICK") {
01290 gg->set_default_orbit_type(CYCLOIDDELAYKICK);
01291 } else if (arg_strs[i] == "CROSS") {
01292 gg->set_default_orbit_type(CROSS);
01293 } else {
01294 std::cerr << "No such default-orbit-type " << arg_strs[i] << std::endl;
01295 }
01296 }
01297 } else if ( arg_strs[i]== "--default-double-support-static-ratio-before" ) {
01298 if (++i < arg_strs.size()) gg->set_default_double_support_static_ratio_before(atof(arg_strs[i].c_str()));
01299 } else if ( arg_strs[i]== "--default-double-support-static-ratio-after" ) {
01300 if (++i < arg_strs.size()) gg->set_default_double_support_static_ratio_after(atof(arg_strs[i].c_str()));
01301 } else if ( arg_strs[i]== "--default-double-support-ratio-swing-before" ) {
01302 if (++i < arg_strs.size()) gg->set_default_double_support_ratio_swing_before(atof(arg_strs[i].c_str()));
01303 } else if ( arg_strs[i]== "--default-double-support-ratio-swing-after" ) {
01304 if (++i < arg_strs.size()) gg->set_default_double_support_ratio_swing_after(atof(arg_strs[i].c_str()));
01305 } else if ( arg_strs[i]== "--swing-trajectory-delay-time-offset" ) {
01306 if (++i < arg_strs.size()) gg->set_swing_trajectory_delay_time_offset(atof(arg_strs[i].c_str()));
01307 } else if ( arg_strs[i]== "--swing-trajectory-final-distance-weight" ) {
01308 if (++i < arg_strs.size()) gg->set_swing_trajectory_final_distance_weight(atof(arg_strs[i].c_str()));
01309 } else if ( arg_strs[i]== "--swing-trajectory-time-offset-xy2z" ) {
01310 if (++i < arg_strs.size()) gg->set_swing_trajectory_time_offset_xy2z(atof(arg_strs[i].c_str()));
01311 } else if ( arg_strs[i]== "--stair-trajectory-way-point-offset" ) {
01312 if (++i < arg_strs.size()) {
01313 coil::vstring strs = coil::split(std::string(arg_strs[i].c_str()), ",");
01314 gg->set_stair_trajectory_way_point_offset(hrp::Vector3(atof(strs[0].c_str()), atof(strs[1].c_str()), atof(strs[2].c_str())));
01315 }
01316 } else if ( arg_strs[i]== "--cycloid-delay-kick-point-offset" ) {
01317 if (++i < arg_strs.size()) {
01318 coil::vstring strs = coil::split(std::string(arg_strs[i].c_str()), ",");
01319 gg->set_cycloid_delay_kick_point_offset(hrp::Vector3(atof(strs[0].c_str()), atof(strs[1].c_str()), atof(strs[2].c_str())));
01320 }
01321 } else if ( arg_strs[i]== "--toe-angle" ) {
01322 if (++i < arg_strs.size()) gg->set_toe_angle(atof(arg_strs[i].c_str()));
01323 } else if ( arg_strs[i]== "--heel-angle" ) {
01324 if (++i < arg_strs.size()) gg->set_heel_angle(atof(arg_strs[i].c_str()));
01325 } else if ( arg_strs[i]== "--toe-heel-phase-ratio" ) {
01326 if (++i < arg_strs.size()) {
01327 coil::vstring strs = coil::split(std::string(arg_strs[i].c_str()), ",");
01328 std::vector<double> ratio;
01329 for (size_t i_th = 0; i_th < strs.size(); i_th++) {
01330 ratio.push_back(atof(strs[i_th].c_str()));
01331 }
01332 std::cerr << "[] ";
01333 gg->set_toe_heel_phase_ratio(ratio);
01334 }
01335 } else if ( arg_strs[i]== "--optional-go-pos-finalize-footstep-num" ) {
01336 if (++i < arg_strs.size()) gg->set_optional_go_pos_finalize_footstep_num(atoi(arg_strs[i].c_str()));
01337 } else if ( arg_strs[i]== "--use-gnuplot" ) {
01338 if (++i < arg_strs.size()) use_gnuplot = (arg_strs[i]=="true");
01339 } else if ( arg_strs[i]== "--use-graph-append" ) {
01340 if (++i < arg_strs.size()) use_graph_append = (arg_strs[i]=="true");
01341 }
01342 }
01343 };
01344
01345 bool check_all_results () const
01346 {
01347 return refzmp_diff_checker.isSmallDiff() && cartzmp_diff_checker.isSmallDiff() && cog_diff_checker.isSmallDiff()
01348 && ssmcpos_diff_checker.isSmallDiff() && ssmcrot_diff_checker.isSmallDiff()
01349 && ssmcposvel_diff_checker.isSmallDiff() && ssmcrotvel_diff_checker.isSmallDiff()
01350 && footpos_diff_checker.isSmallDiff() && footrot_diff_checker.isSmallDiff()
01351 && zmpoffset_diff_checker.isSmallDiff()
01352 && footposvel_diff_checker.isSmallDiff() && footrotvel_diff_checker.isSmallDiff()
01353 && zmp_error_checker.isSmallError() && cogzmp_error_checker.isSmallError()
01354 && is_step_time_valid && is_toe_heel_dif_angle_valid && is_toe_heel_zmp_offset_x_valid
01355 && is_contact_states_swing_support_time_validity;
01356 };
01357 };
01358
01359 class testGaitGeneratorHRP2JSK : public testGaitGenerator
01360 {
01361 public:
01362 testGaitGeneratorHRP2JSK () : testGaitGenerator(0.004)
01363 {
01364 cog = 1e-3*hrp::Vector3(6.785, 1.54359, 806.831);
01365 leg_pos.push_back(hrp::Vector3(0,1e-3*-105,0));
01366 leg_pos.push_back(hrp::Vector3(0,1e-3* 105,0));
01367 all_limbs.push_back("rleg");
01368 all_limbs.push_back("lleg");
01369 gg = new gait_generator(dt, leg_pos, all_limbs, 1e-3*150, 1e-3*50, 10, 1e-3*50, 1e-3*50*0.5, 10*0.5);
01370 };
01371 };
01372
01373 void print_usage ()
01374 {
01375 std::cerr << "Usage : testGaitGenerator [test-name] [option]" << std::endl;
01376 std::cerr << " [test-name] should be:" << std::endl;
01377 std::cerr << " --test0 : Set foot steps" << std::endl;
01378 std::cerr << " --test1 : Go pos x,y,th combination" << std::endl;
01379 std::cerr << " --test2 : Go pos x" << std::endl;
01380 std::cerr << " --test3 : Go pos y" << std::endl;
01381 std::cerr << " --test4 : Go pos th" << std::endl;
01382 std::cerr << " --test5 : Set foot steps with Z change" << std::endl;
01383 std::cerr << " --test6 : Go single step" << std::endl;
01384 std::cerr << " --test7 : Toe heel walk" << std::endl;
01385 std::cerr << " --test8 : Toe heel walk on slope" << std::endl;
01386 std::cerr << " --test9 : Stair walk" << std::endl;
01387 std::cerr << " --test10 : Stair walk + toe heel contact" << std::endl;
01388 std::cerr << " --test11 : Foot rot change" << std::endl;
01389 std::cerr << " --test12 : Change step param in set foot steps" << std::endl;
01390 std::cerr << " --test13 : Arbitrary leg switching" << std::endl;
01391 std::cerr << " --test14 : kick walk" << std::endl;
01392 std::cerr << " --test15 : Stair walk down" << std::endl;
01393 std::cerr << " --test16 : Set foot steps with param (toe heel contact)" << std::endl;
01394 std::cerr << " --test17 : Test goVelocity (dx = 0.1, dy = 0.05, dth = 10.0)" << std::endl;
01395 std::cerr << " --test18 : Test goVelocity with changing velocity (translation and rotation)" << std::endl;
01396 std::cerr << " --test19 : Change stride parameter (translate)" << std::endl;
01397 std::cerr << " --test20 : Change stride parameter (translate+rotate)" << std::endl;
01398 std::cerr << " [option] should be:" << std::endl;
01399 std::cerr << " --use-gnuplot : Use gnuplot and dump eps file to /tmp. (true/false, true by default)" << std::endl;
01400 std::cerr << " --use-graph-append : Append generated graph to /tmp/testGaitGenerator.jpg. (true/false, false by default)" << std::endl;
01401 std::cerr << " other options : for GaitGenerator" << std::endl;
01402 };
01403
01404 int main(int argc, char* argv[])
01405 {
01406 int ret = 0;
01407 if (argc >= 2) {
01408 testGaitGeneratorHRP2JSK tgg;
01409 for (int i = 1; i < argc; ++ i) {
01410 tgg.arg_strs.push_back(std::string(argv[i]));
01411 }
01412 if (std::string(argv[1]) == "--test0") {
01413 tgg.test0();
01414 } else if (std::string(argv[1]) == "--test1") {
01415 tgg.test1();
01416 } else if (std::string(argv[1]) == "--test2") {
01417 tgg.test2();
01418 } else if (std::string(argv[1]) == "--test3") {
01419 tgg.test3();
01420 } else if (std::string(argv[1]) == "--test4") {
01421 tgg.test4();
01422 } else if (std::string(argv[1]) == "--test5") {
01423 tgg.test5();
01424 } else if (std::string(argv[1]) == "--test6") {
01425 tgg.test6();
01426 } else if (std::string(argv[1]) == "--test7") {
01427 tgg.test7();
01428 } else if (std::string(argv[1]) == "--test8") {
01429 tgg.test8();
01430 } else if (std::string(argv[1]) == "--test9") {
01431 tgg.test9();
01432 } else if (std::string(argv[1]) == "--test10") {
01433 tgg.test10();
01434 } else if (std::string(argv[1]) == "--test11") {
01435 tgg.test11();
01436 } else if (std::string(argv[1]) == "--test12") {
01437 tgg.test12();
01438 } else if (std::string(argv[1]) == "--test13") {
01439 tgg.test13();
01440 } else if (std::string(argv[1]) == "--test14") {
01441 tgg.test14();
01442 } else if (std::string(argv[1]) == "--test15") {
01443 tgg.test15();
01444 } else if (std::string(argv[1]) == "--test16") {
01445 tgg.test16();
01446 } else if (std::string(argv[1]) == "--test17") {
01447 tgg.test17();
01448 } else if (std::string(argv[1]) == "--test18") {
01449 tgg.test18();
01450 } else if (std::string(argv[1]) == "--test19") {
01451 tgg.test19();
01452 } else if (std::string(argv[1]) == "--test20") {
01453 tgg.test20();
01454 } else {
01455 print_usage();
01456 ret = 1;
01457 }
01458 ret = (tgg.check_all_results()?0:2);
01459 } else {
01460 print_usage();
01461 ret = 1;
01462 }
01463 return ret;
01464 }
01465