00001
00002 #ifndef GAITGENERATOR_H
00003 #define GAITGENERATOR_H
00004 #include "PreviewController.h"
00005 #include "../ImpedanceController/RatsMatrix.h"
00006 #include "interpolator.h"
00007 #include <vector>
00008 #include <queue>
00009 #include <boost/assign.hpp>
00010 #include <boost/lambda/lambda.hpp>
00011 #include <boost/shared_ptr.hpp>
00012
00013 #ifdef FOR_TESTGAITGENERATOR
00014 #warning "Compile for testGaitGenerator"
00015 #endif // FOR_TESTGAITGENERATOR
00016
00017 namespace rats
00018 {
00019 void cycloid_midpoint (hrp::Vector3& ret,
00020 const double ratio, const hrp::Vector3& start,
00021 const hrp::Vector3& goal, const double height,
00022 const double default_top_ratio = 0.5);
00023 void multi_mid_coords (coordinates& mid_coords, const std::vector<coordinates>& cs, const double eps = 0.001);
00024
00025 enum orbit_type {SHUFFLING, CYCLOID, RECTANGLE, STAIR, CYCLOIDDELAY, CYCLOIDDELAYKICK, CROSS};
00026 enum leg_type {RLEG, LLEG, RARM, LARM, BOTH, ALL};
00027 enum stride_limitation_type {SQUARE, CIRCLE};
00028 std::string leg_type_to_leg_type_string (const leg_type l_r);
00029
00030 struct step_node
00031 {
00032 leg_type l_r;
00033 coordinates worldcoords;
00034 double step_height, step_time, toe_angle, heel_angle;
00035 step_node () : l_r(RLEG), worldcoords(coordinates()),
00036 step_height(), step_time(),
00037 toe_angle(), heel_angle(){};
00038 step_node (const leg_type _l_r, const coordinates& _worldcoords,
00039 const double _step_height, const double _step_time,
00040 const double _toe_angle, const double _heel_angle)
00041 : l_r(_l_r), worldcoords(_worldcoords),
00042 step_height(_step_height), step_time(_step_time),
00043 toe_angle(_toe_angle), heel_angle(_heel_angle) {};
00044 step_node (const std::string& _l_r, const coordinates& _worldcoords,
00045 const double _step_height, const double _step_time,
00046 const double _toe_angle, const double _heel_angle)
00047 : l_r((_l_r == "rleg") ? RLEG :
00048 (_l_r == "rarm") ? RARM :
00049 (_l_r == "larm") ? LARM :
00050 LLEG), worldcoords(_worldcoords),
00051 step_height(_step_height), step_time(_step_time),
00052 toe_angle(_toe_angle), heel_angle(_heel_angle) {};
00053 friend std::ostream &operator<<(std::ostream &os, const step_node &sn)
00054 {
00055 os << "footstep" << std::endl;
00056 os << " name = [" << ((sn.l_r==LLEG)?std::string("lleg"):
00057 (sn.l_r==RARM)?std::string("rarm"):
00058 (sn.l_r==LARM)?std::string("larm"):
00059 std::string("rleg")) << "]" << std::endl;
00060 os << " pos =";
00061 os << (sn.worldcoords.pos).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]")) << std::endl;
00062 os << " rot =";
00063 os << (sn.worldcoords.rot).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", "", " [", "]")) << std::endl;
00064 os << " step_height = " << sn.step_height << "[m], step_time = " << sn.step_time << "[s], "
00065 << "toe_angle = " << sn.toe_angle << "[deg], heel_angle = " << sn.heel_angle << "[deg]";
00066 return os;
00067 };
00068 };
00069
00070
00071 struct footstep_parameter
00072 {
00073
00074
00075
00076 std::vector<hrp::Vector3> leg_default_translate_pos;
00077
00078 double stride_fwd_x, stride_outside_y, stride_outside_theta, stride_bwd_x, stride_inside_y, stride_inside_theta;
00079 footstep_parameter (const std::vector<hrp::Vector3>& _leg_pos,
00080 const double _stride_fwd_x, const double _stride_outside_y, const double _stride_outside_theta,
00081 const double _stride_bwd_x, const double _stride_inside_y, const double _stride_inside_theta)
00082 : leg_default_translate_pos(_leg_pos),
00083 stride_fwd_x(_stride_fwd_x), stride_outside_y(_stride_outside_y), stride_outside_theta(_stride_outside_theta),
00084 stride_bwd_x(_stride_bwd_x), stride_inside_y(_stride_inside_y), stride_inside_theta(_stride_inside_theta) {};
00085 };
00086
00087
00088 struct velocity_mode_parameter
00089 {
00090
00091 double velocity_x, velocity_y, velocity_theta;
00092 void set (const double _vx, const double _vy, const double _vth)
00093 {
00094 velocity_x = _vx;
00095 velocity_y = _vy;
00096 velocity_theta = _vth;
00097 };
00098 velocity_mode_parameter ()
00099 :velocity_x(0), velocity_y(0), velocity_theta(0) {};
00100 };
00101
00102
00103
00104
00105
00106
00107
00108
00109
00110
00111 enum toe_heel_phase {SOLE0, SOLE2TOE, TOE2SOLE, SOLE1, SOLE2HEEL, HEEL2SOLE, SOLE2, NUM_TH_PHASES};
00112 static double no_using_toe_heel_ratio = 1.0;
00113 static double using_toe_heel_ratio = 0.0;
00114
00115 enum toe_heel_type {SOLE, TOE, HEEL};
00116 struct toe_heel_types
00117 {
00118 toe_heel_type src_type, dst_type;
00119 toe_heel_types (const toe_heel_type _src_type = SOLE, const toe_heel_type _dst_type = SOLE) : src_type(_src_type), dst_type(_dst_type)
00120 {
00121 };
00122 };
00123
00124
00125 class toe_heel_phase_counter
00126 {
00127 double toe_heel_phase_ratio[NUM_TH_PHASES];
00128 size_t toe_heel_phase_count[NUM_TH_PHASES], one_step_count;
00129 bool calc_toe_heel_phase_count_from_raio ()
00130 {
00131 double ratio_sum = 0.0;
00132 for (size_t i = 0; i < NUM_TH_PHASES; i++) {
00133 ratio_sum += toe_heel_phase_ratio[i];
00134 toe_heel_phase_count[i] = static_cast<size_t>(one_step_count * ratio_sum);
00135 }
00136 };
00137 public:
00138 toe_heel_phase_counter () : one_step_count(0)
00139 {
00140 toe_heel_phase_ratio[SOLE0] = 0.05;
00141 toe_heel_phase_ratio[SOLE2TOE] = 0.25;
00142 toe_heel_phase_ratio[TOE2SOLE] = 0.2;
00143 toe_heel_phase_ratio[SOLE1] = 0.0;
00144 toe_heel_phase_ratio[SOLE2HEEL] = 0.2;
00145 toe_heel_phase_ratio[HEEL2SOLE] = 0.25;
00146 toe_heel_phase_ratio[SOLE2] = 0.05;
00147 };
00148 bool check_toe_heel_phase_ratio_validity (const std::vector<double>& ratio)
00149 {
00150 bool ret = true;
00151
00152 if (ratio.size() != NUM_TH_PHASES) {
00153 ret = false;
00154 }
00155
00156 double sum_ratio = 0.0;
00157 for (int i = 0; i < NUM_TH_PHASES; i++) sum_ratio += ratio[i];
00158 if (std::fabs(sum_ratio-1.0) > 1e-3) {
00159 ret = false;
00160 }
00161 if (!ret) {
00162 std::cerr << "toe_heel_phase_ratio is not set, "
00163 << ", required length = " << NUM_TH_PHASES << " != input length " << ratio.size()
00164 << ", sum_ratio = " << sum_ratio << " is not 1.0."
00165 << std::endl;
00166 } else {
00167 std::cerr << "toe_heel_phase_ratio is successfully set." << std::endl;
00168 }
00169 return ret;
00170 };
00171
00172 void set_one_step_count (const size_t _count)
00173 {
00174 one_step_count = _count;
00175 calc_toe_heel_phase_count_from_raio();
00176 };
00177 bool set_toe_heel_phase_ratio (const std::vector<double>& ratio)
00178 {
00179 if (check_toe_heel_phase_ratio_validity(ratio)) {
00180 for (size_t i = 0; i < NUM_TH_PHASES; i++) toe_heel_phase_ratio[i] = ratio[i];
00181 return true;
00182 } else {
00183 return false;
00184 }
00185 };
00186
00187 void get_toe_heel_phase_ratio (std::vector<double>& ratio) const
00188 {
00189 for (size_t i = 0; i < NUM_TH_PHASES; i++) ratio[i] = toe_heel_phase_ratio[i];
00190 };
00191
00192 bool is_phase_starting (const size_t current_count, const toe_heel_phase _phase) const
00193 {
00194 return (current_count == toe_heel_phase_count[_phase]);
00195 };
00196 bool is_between_phases (const size_t current_count, const toe_heel_phase phase0, const toe_heel_phase phase1) const
00197 {
00198 return (toe_heel_phase_count[phase0] <= current_count) && (current_count < toe_heel_phase_count[phase1]);
00199 };
00200 bool is_between_phases (const size_t current_count, const toe_heel_phase phase1) const
00201 {
00202 return (current_count < toe_heel_phase_count[phase1]);
00203 };
00204 bool is_no_SOLE1_phase () const { return toe_heel_phase_count[TOE2SOLE] == toe_heel_phase_count[SOLE1]; };
00205
00206 double calc_phase_period (const toe_heel_phase start_phase, const toe_heel_phase goal_phase, const double _dt) const
00207 {
00208 return _dt * (toe_heel_phase_count[goal_phase]-toe_heel_phase_count[start_phase]);
00209 };
00210
00211
00212 double calc_phase_ratio (const size_t current_count, const toe_heel_phase start_phase, const toe_heel_phase goal_phase) const
00213 {
00214 return static_cast<double>(current_count-toe_heel_phase_count[start_phase]) / (toe_heel_phase_count[goal_phase]-toe_heel_phase_count[start_phase]);
00215 };
00216
00217
00218 double calc_phase_ratio (const size_t current_count, const toe_heel_phase goal_phase) const
00219 {
00220 return static_cast<double>(current_count) / (toe_heel_phase_count[goal_phase]);
00221 };
00222
00223
00224
00225 double calc_phase_ratio_for_toe_heel_transition (const size_t current_count) const
00226 {
00227 if (is_between_phases(current_count, SOLE0)) {
00228
00229 return 1-calc_phase_ratio(current_count, SOLE0);
00230 } else if (is_between_phases(current_count, HEEL2SOLE, SOLE2) || toe_heel_phase_count[SOLE2] == current_count) {
00231
00232 return calc_phase_ratio(current_count, HEEL2SOLE, SOLE2);
00233 } else {
00234
00235 return using_toe_heel_ratio;
00236 }
00237 };
00238 };
00239
00240
00241 class toe_heel_type_checker
00242 {
00243 private:
00244 double toe_check_thre, heel_check_thre;
00245 public:
00246 toe_heel_type_checker () : toe_check_thre(0), heel_check_thre(0)
00247 {
00248 };
00249 toe_heel_type_checker (const double _toe_check_thre, const double _heel_check_thre) : toe_check_thre(_toe_check_thre), heel_check_thre(_heel_check_thre)
00250 {
00251 };
00252 toe_heel_type check_toe_heel_type_from_swing_support_coords (const coordinates& swing_coords, const coordinates& support_coords, const double toe_pos_offset_x, const double heel_pos_offset_x) const
00253 {
00254 hrp::Vector3 local_toe_pos = support_coords.rot.transpose() * (swing_coords.rot * hrp::Vector3(toe_pos_offset_x,0,0) + swing_coords.pos - support_coords.pos);
00255 hrp::Vector3 local_heel_pos = support_coords.rot.transpose() * (swing_coords.rot * hrp::Vector3(heel_pos_offset_x,0,0) + swing_coords.pos - support_coords.pos);
00256 if (local_toe_pos(2) < -50*1e-3 && (local_toe_pos(0) + toe_check_thre < 0 || local_heel_pos(0) - heel_check_thre > 0) ) {
00257 return TOE;
00258 } else if (local_toe_pos(0) + toe_check_thre < 0) {
00259 return TOE;
00260 } else if (local_heel_pos(0) - heel_check_thre > 0) {
00261 return HEEL;
00262 } else {
00263 return SOLE;
00264 }
00265 };
00266 void print_param (const std::string print_str = "") const
00267 {
00268 std::cerr << "[" << print_str << "] toe_check_thre = " << toe_check_thre << ", heel_check_thre = " << heel_check_thre << std::endl;
00269 };
00270
00271 void set_toe_check_thre (const double _toe_check_thre) { toe_check_thre = _toe_check_thre; };
00272 void set_heel_check_thre (const double _heel_check_thre) { heel_check_thre = _heel_check_thre; };
00273
00274 double get_toe_check_thre () const { return toe_check_thre; };
00275 double get_heel_check_thre () const { return heel_check_thre; };
00276 };
00277
00278 double set_value_according_to_toe_heel_type (const toe_heel_type tht, const double toe_value, const double heel_value, const double default_value);
00279
00280
00281 class refzmp_generator
00282 {
00283 #ifdef HAVE_MAIN
00284 public:
00285 #endif
00286 std::vector<hrp::Vector3> refzmp_cur_list;
00287 std::map<leg_type, double> zmp_weight_map;
00288 std::vector< std::vector<hrp::Vector3> > foot_x_axises_list;
00289 std::vector< std::vector<leg_type> > swing_leg_types_list;
00290 std::vector<size_t> step_count_list;
00291 std::vector<toe_heel_types> toe_heel_types_list;
00292 std::vector<hrp::Vector3> default_zmp_offsets;
00293 size_t refzmp_index, refzmp_count, one_step_count;
00294 double toe_zmp_offset_x, heel_zmp_offset_x;
00295 double dt;
00296 toe_heel_phase_counter thp;
00297 bool use_toe_heel_transition, use_toe_heel_auto_set;
00298 boost::shared_ptr<interpolator> zmp_weight_interpolator;
00299 void calc_current_refzmp (hrp::Vector3& ret, std::vector<hrp::Vector3>& swing_foot_zmp_offsets, const double default_double_support_ratio_before, const double default_double_support_ratio_after, const double default_double_support_static_ratio_before, const double default_double_support_static_ratio_after);
00300 const bool is_start_double_support_phase () const { return refzmp_index == 0; };
00301 const bool is_second_phase () const { return refzmp_index == 1; };
00302 const bool is_second_last_phase () const { return refzmp_index == refzmp_cur_list.size()-2; };
00303 const bool is_end_double_support_phase () const { return refzmp_index == refzmp_cur_list.size() - 1; };
00304 #ifndef HAVE_MAIN
00305 public:
00306 #endif
00307 refzmp_generator(const double _dt)
00308 : refzmp_cur_list(), foot_x_axises_list(), swing_leg_types_list(), step_count_list(), toe_heel_types_list(), default_zmp_offsets(),
00309 refzmp_index(0), refzmp_count(0), one_step_count(0),
00310 toe_zmp_offset_x(0), heel_zmp_offset_x(0), dt(_dt),
00311 thp(), use_toe_heel_transition(false), use_toe_heel_auto_set(false)
00312 {
00313 default_zmp_offsets.push_back(hrp::Vector3::Zero());
00314 default_zmp_offsets.push_back(hrp::Vector3::Zero());
00315 default_zmp_offsets.push_back(hrp::Vector3::Zero());
00316 default_zmp_offsets.push_back(hrp::Vector3::Zero());
00317 double zmp_weight_initial_value[4] = {1.0, 1.0, 0.1, 0.1};
00318 zmp_weight_map = boost::assign::map_list_of<leg_type, double>(RLEG, zmp_weight_initial_value[0])(LLEG, zmp_weight_initial_value[1])(RARM, zmp_weight_initial_value[2])(LARM, zmp_weight_initial_value[3]);
00319 zmp_weight_interpolator = boost::shared_ptr<interpolator>(new interpolator(4, dt));
00320 zmp_weight_interpolator->set(zmp_weight_initial_value);
00321 zmp_weight_interpolator->setName("GaitGenerator zmp_weight_interpolator");
00322 };
00323 ~refzmp_generator()
00324 {
00325 };
00326 void remove_refzmp_cur_list_over_length (const size_t len)
00327 {
00328 while ( refzmp_cur_list.size() > len) refzmp_cur_list.pop_back();
00329 while ( foot_x_axises_list.size() > len) foot_x_axises_list.pop_back();
00330 while ( swing_leg_types_list.size() > len) swing_leg_types_list.pop_back();
00331 while ( step_count_list.size() > len) step_count_list.pop_back();
00332 while ( toe_heel_types_list.size() > len) toe_heel_types_list.pop_back();
00333 };
00334 void reset (const size_t _refzmp_count)
00335 {
00336 set_indices(0);
00337 one_step_count = _refzmp_count;
00338 set_refzmp_count(_refzmp_count);
00339 refzmp_cur_list.clear();
00340 foot_x_axises_list.clear();
00341 swing_leg_types_list.clear();
00342 step_count_list.clear();
00343 toe_heel_types_list.clear();
00344 thp.set_one_step_count(one_step_count);
00345 };
00346 void push_refzmp_from_footstep_nodes_for_dual (const std::vector<step_node>& fns,
00347 const std::vector<step_node>& _support_leg_steps,
00348 const std::vector<step_node>& _swing_leg_steps);
00349 void push_refzmp_from_footstep_nodes_for_single (const std::vector<step_node>& fns, const std::vector<step_node>& _support_leg_steps, const toe_heel_types& tht);
00350 void update_refzmp ();
00351
00352 void set_indices (const size_t idx) { refzmp_index = idx; };
00353 void set_refzmp_count(const size_t _refzmp_count) { refzmp_count = _refzmp_count; };
00354 void set_default_zmp_offsets(const std::vector<hrp::Vector3>& tmp) { default_zmp_offsets = tmp; };
00355 void set_toe_zmp_offset_x (const double _off) { toe_zmp_offset_x = _off; };
00356 void set_heel_zmp_offset_x (const double _off) { heel_zmp_offset_x = _off; };
00357 void set_use_toe_heel_transition (const bool _u) { use_toe_heel_transition = _u; };
00358 void set_use_toe_heel_auto_set (const bool _u) { use_toe_heel_auto_set = _u; };
00359 void set_zmp_weight_map (const std::map<leg_type, double> _map) {
00360 double zmp_weight_array[4] = {_map.find(RLEG)->second, _map.find(LLEG)->second, _map.find(RARM)->second, _map.find(LARM)->second};
00361 if (zmp_weight_interpolator->isEmpty()) {
00362 zmp_weight_interpolator->clear();
00363 double zmp_weight_initial_value[4] = {zmp_weight_map[RLEG], zmp_weight_map[LLEG], zmp_weight_map[RARM], zmp_weight_map[LARM]};
00364 zmp_weight_interpolator->set(zmp_weight_initial_value);
00365 zmp_weight_interpolator->setGoal(zmp_weight_array, 2.0, true);
00366 } else {
00367 std::cerr << "zmp_weight_map cannot be set because interpolating." << std::endl;
00368 }
00369 };
00370 bool set_toe_heel_phase_ratio (const std::vector<double>& ratio) { return thp.set_toe_heel_phase_ratio(ratio); };
00371
00372 bool get_current_refzmp (hrp::Vector3& rzmp, std::vector<hrp::Vector3>& swing_foot_zmp_offsets, const double default_double_support_ratio_before, const double default_double_support_ratio_after, const double default_double_support_static_ratio_before, const double default_double_support_static_ratio_after)
00373 {
00374 if (refzmp_cur_list.size() > refzmp_index ) calc_current_refzmp(rzmp, swing_foot_zmp_offsets, default_double_support_ratio_before, default_double_support_ratio_after, default_double_support_static_ratio_before, default_double_support_static_ratio_after);
00375 return refzmp_cur_list.size() > refzmp_index;
00376 };
00377 const hrp::Vector3& get_refzmp_cur () const { return refzmp_cur_list.front(); };
00378 const hrp::Vector3& get_default_zmp_offset (const leg_type lt) const { return default_zmp_offsets[lt]; };
00379 double get_toe_zmp_offset_x () const { return toe_zmp_offset_x; };
00380 double get_heel_zmp_offset_x () const { return heel_zmp_offset_x; };
00381 bool get_use_toe_heel_transition () const { return use_toe_heel_transition; };
00382 bool get_use_toe_heel_auto_set () const { return use_toe_heel_auto_set; };
00383 const std::map<leg_type, double> get_zmp_weight_map () const { return zmp_weight_map; };
00384 void proc_zmp_weight_map_interpolation () {
00385 if (!zmp_weight_interpolator->isEmpty()) {
00386 double zmp_weight_output[4];
00387 zmp_weight_interpolator->get(zmp_weight_output, true);
00388 zmp_weight_map = boost::assign::map_list_of<leg_type, double>(RLEG, zmp_weight_output[0])(LLEG, zmp_weight_output[1])(RARM, zmp_weight_output[2])(LARM, zmp_weight_output[3]);
00389 }
00390 };
00391 #ifdef FOR_TESTGAITGENERATOR
00392 std::vector<hrp::Vector3> get_default_zmp_offsets() const { return default_zmp_offsets; };
00393 #endif // FOR_TESTGAITGENERATOR
00394 };
00395
00396 class delay_hoffarbib_trajectory_generator
00397 {
00398 private:
00399 hrp::Vector3 pos, vel, acc;
00400 double dt;
00401
00402 std::vector<hrp::Vector3> point_vec;
00403 std::vector<double> distance_vec;
00404 std::vector<double> sum_distance_vec;
00405 double total_path_length;
00406
00407 void hoffarbib_interpolation (double& _pos, double& _vel, double& _acc, const double tmp_remain_time, const double tmp_goal, const double tmp_goal_vel = 0, const double tmp_goal_acc = 0)
00408 {
00409 double jerk = (-9.0/ tmp_remain_time) * (_acc - tmp_goal_acc / 3.0) +
00410 (-36.0 / (tmp_remain_time * tmp_remain_time)) * (tmp_goal_vel * 2.0 / 3.0 + _vel) +
00411 (60.0 / (tmp_remain_time * tmp_remain_time * tmp_remain_time)) * (tmp_goal - _pos);
00412 _acc = _acc + dt * jerk;
00413 _vel = _vel + dt * _acc;
00414 _pos = _pos + dt * _vel;
00415 };
00416 protected:
00417 double time_offset;
00418 double final_distance_weight;
00419 double time_offset_xy2z;
00420 size_t one_step_count, current_count, double_support_count_before, double_support_count_after;
00421 virtual double calc_antecedent_path (const hrp::Vector3& start, const hrp::Vector3& goal, const double height) = 0;
00422 public:
00423 delay_hoffarbib_trajectory_generator () : time_offset(0.35), final_distance_weight(1.0), time_offset_xy2z(0), one_step_count(0), current_count(0), double_support_count_before(0), double_support_count_after(0) {};
00424 ~delay_hoffarbib_trajectory_generator() { };
00425 void set_dt (const double _dt) { dt = _dt; };
00426 void set_swing_trajectory_delay_time_offset (const double _time_offset) { time_offset = _time_offset; };
00427 void set_swing_trajectory_final_distance_weight (const double _final_distance_weight) { final_distance_weight = _final_distance_weight; };
00428 void set_swing_trajectory_time_offset_xy2z (const double _tmp) { time_offset_xy2z = _tmp; };
00429 void reset (const size_t _one_step_len, const double default_double_support_ratio_before, const double default_double_support_ratio_after)
00430 {
00431 one_step_count = _one_step_len;
00432 current_count = 0;
00433 double_support_count_before = (default_double_support_ratio_before*one_step_count);
00434 double_support_count_after = (default_double_support_ratio_after*one_step_count);
00435 };
00436 void reset_all (const double _dt, const size_t _one_step_len,
00437 const double default_double_support_ratio_before, const double default_double_support_ratio_after,
00438 const double _time_offset, const double _final_distance_weight, const double _time_offset_xy2z)
00439 {
00440 set_dt(_dt);
00441 reset (_one_step_len, default_double_support_ratio_before, default_double_support_ratio_after);
00442 set_swing_trajectory_delay_time_offset(_time_offset);
00443 set_swing_trajectory_final_distance_weight(_final_distance_weight);
00444 set_swing_trajectory_time_offset_xy2z(_time_offset_xy2z);
00445 };
00446 void get_trajectory_point (hrp::Vector3& ret, const hrp::Vector3& start, const hrp::Vector3& goal, const double height)
00447 {
00448 if ( current_count <= double_support_count_before ) {
00449 pos = start;
00450 vel = hrp::Vector3::Zero();
00451 acc = hrp::Vector3::Zero();
00452 } else if ( current_count >= one_step_count - double_support_count_after ) {
00453 pos = goal;
00454 vel = hrp::Vector3::Zero();
00455 acc = hrp::Vector3::Zero();
00456 }
00457 if ( double_support_count_before <= current_count && current_count < one_step_count - double_support_count_after ) {
00458 size_t swing_remain_count = one_step_count - current_count - double_support_count_after;
00459 size_t swing_one_step_count = one_step_count - double_support_count_before - double_support_count_after;
00460 double final_path_distance_ratio = calc_antecedent_path(start, goal, height);
00461 size_t tmp_time_offset_count = time_offset/dt;
00462
00463 size_t final_path_count = final_path_distance_ratio * swing_one_step_count;
00464 if (final_path_count>static_cast<size_t>(time_offset_xy2z/dt)) final_path_count = static_cast<size_t>(time_offset_xy2z/dt);
00465
00466 if (swing_remain_count > final_path_count+tmp_time_offset_count) {
00467 hrp::Vector3 tmpgoal = interpolate_antecedent_path((swing_one_step_count - swing_remain_count) / static_cast<double>(swing_one_step_count - (final_path_count+tmp_time_offset_count)));
00468 for (size_t i = 0; i < 2; i++) hoffarbib_interpolation (pos(i), vel(i), acc(i), time_offset, tmpgoal(i));
00469 } else if (swing_remain_count > final_path_count) {
00470 double tmprt = (swing_remain_count-final_path_count)*dt;
00471 for (size_t i = 0; i < 2; i++) hoffarbib_interpolation (pos(i), vel(i), acc(i), tmprt, goal(i));
00472 } else {
00473 for (size_t i = 0; i < 2; i++) pos(i) = goal(i);
00474 }
00475
00476 if (swing_remain_count > tmp_time_offset_count) {
00477 hrp::Vector3 tmpgoal = interpolate_antecedent_path((swing_one_step_count - swing_remain_count) / static_cast<double>(swing_one_step_count - tmp_time_offset_count));
00478 hoffarbib_interpolation (pos(2), vel(2), acc(2), time_offset, tmpgoal(2));
00479 } else if (swing_remain_count > 0) {
00480 hoffarbib_interpolation (pos(2), vel(2), acc(2), swing_remain_count*dt, goal(2));
00481 } else {
00482 pos(2) = goal(2);
00483 }
00484 }
00485 ret = pos;
00486 current_count++;
00487 };
00488 double get_swing_trajectory_delay_time_offset () const { return time_offset; };
00489 double get_swing_trajectory_final_distance_weight () const { return final_distance_weight; };
00490 double get_swing_trajectory_time_offset_xy2z () const { return time_offset_xy2z; };
00491
00492
00493
00494
00495 double calc_antecedent_path_base (const std::vector<hrp::Vector3> org_point_vec)
00496 {
00497 total_path_length = 0;
00498 point_vec.clear();
00499 distance_vec.clear();
00500 point_vec.push_back(org_point_vec.front());
00501
00502 for (size_t i = 0; i < org_point_vec.size()-1; i++) {
00503 double tmp_distance = (org_point_vec[i+1]-org_point_vec[i]).norm();
00504 if (i==org_point_vec.size()-2) tmp_distance*=final_distance_weight;
00505 if ( tmp_distance > 1e-5 ) {
00506 point_vec.push_back(org_point_vec[i+1]);
00507 distance_vec.push_back(tmp_distance);
00508 total_path_length += tmp_distance;
00509 }
00510 }
00511 if ( total_path_length < 1e-5 ) {
00512 return 0;
00513 }
00514
00515
00516
00517 sum_distance_vec.clear();
00518 sum_distance_vec.push_back(0);
00519 double tmp_dist = 0;
00520 for (size_t i = 0; i < distance_vec.size(); i++) {
00521 sum_distance_vec.push_back(tmp_dist + distance_vec[i]);
00522 tmp_dist += distance_vec[i];
00523 }
00524 return distance_vec.back()/total_path_length;
00525 };
00526 hrp::Vector3 interpolate_antecedent_path (const double tmp_ratio) const
00527 {
00528 if ( total_path_length < 1e-5 ) {
00529 return point_vec.back();
00530 }
00531
00532 double current_length = tmp_ratio * total_path_length;
00533 for (size_t i = 0; i < sum_distance_vec.size(); i++) {
00534 if ( (sum_distance_vec[i] <= current_length) && (current_length <= sum_distance_vec[i+1]) ) {
00535 double tmpr = ((current_length - sum_distance_vec[i]) / distance_vec[i]);
00536 return ((1-tmpr) * point_vec[i] + tmpr * point_vec[1+i]);
00537 }
00538 }
00539
00540 if (current_length < 0) return point_vec.front();
00541 else point_vec.back();
00542 };
00543 };
00544
00545 class rectangle_delay_hoffarbib_trajectory_generator : public delay_hoffarbib_trajectory_generator
00546 {
00547 double calc_antecedent_path (const hrp::Vector3& start, const hrp::Vector3& goal, const double height)
00548 {
00549 std::vector<hrp::Vector3> rectangle_path;
00550 double max_height = std::max(start(2), goal(2))+height;
00551 rectangle_path.push_back(start);
00552 rectangle_path.push_back(hrp::Vector3(start(0), start(1), max_height));
00553 rectangle_path.push_back(hrp::Vector3(goal(0), goal(1), max_height));
00554 rectangle_path.push_back(goal);
00555 return calc_antecedent_path_base(rectangle_path);
00556 };
00557 };
00558
00559 class stair_delay_hoffarbib_trajectory_generator : public delay_hoffarbib_trajectory_generator
00560 {
00561 hrp::Vector3 way_point_offset;
00562 double calc_antecedent_path (const hrp::Vector3& start, const hrp::Vector3& goal, const double height)
00563 {
00564 std::vector<hrp::Vector3> path;
00565 double max_height = std::max(start(2), goal(2))+height;
00566 hrp::Vector3 diff_vec = goal - start;
00567 diff_vec(2) = 0.0;
00568 path.push_back(start);
00569
00570
00571 if ( diff_vec.norm() > 1e-4 && (goal(2) - start(2)) > 0.02) {
00572 path.push_back(hrp::Vector3(start+-1*way_point_offset(0)*diff_vec.normalized()+hrp::Vector3(0,0,way_point_offset(2)+max_height-start(2))));
00573 }
00574 path.push_back(hrp::Vector3(start(0), start(1), max_height));
00575 path.push_back(hrp::Vector3(goal(0), goal(1), max_height));
00576
00577 if ( diff_vec.norm() > 1e-4 && (start(2) - goal(2)) > 0.02) {
00578 path.push_back(hrp::Vector3(goal+way_point_offset(0)*diff_vec.normalized()+hrp::Vector3(0,0,way_point_offset(2)+max_height-goal(2))));
00579 }
00580
00581
00582
00583 path.push_back(goal);
00584 return calc_antecedent_path_base(path);
00585 };
00586 public:
00587 stair_delay_hoffarbib_trajectory_generator () : delay_hoffarbib_trajectory_generator(), way_point_offset(hrp::Vector3(0.03, 0.0, 0.0)) {};
00588 ~stair_delay_hoffarbib_trajectory_generator () {};
00589 void set_stair_trajectory_way_point_offset (const hrp::Vector3 _offset) { way_point_offset = _offset; };
00590 hrp::Vector3 get_stair_trajectory_way_point_offset() const { return way_point_offset; };
00591 };
00592
00593 class cycloid_delay_hoffarbib_trajectory_generator : public delay_hoffarbib_trajectory_generator
00594 {
00595 double calc_antecedent_path (const hrp::Vector3& start, const hrp::Vector3& goal, const double height)
00596 {
00597 std::vector<hrp::Vector3> cycloid_path;
00598 hrp::Vector3 tmpv, via_goal(goal);
00599 double ratio = 0.4;
00600 via_goal(2) += ratio*height;
00601 double tmpheight = ((start(2)+goal(2))/2.0+height-(start(2)+via_goal(2))/2.0);
00602 cycloid_path.push_back(start);
00603 cycloid_midpoint(tmpv, 0.2, start, via_goal, tmpheight);
00604 cycloid_path.push_back(tmpv);
00605 cycloid_midpoint(tmpv, 0.4, start, via_goal, tmpheight);
00606 cycloid_path.push_back(tmpv);
00607 cycloid_midpoint(tmpv, 0.6, start, via_goal, tmpheight);
00608 cycloid_path.push_back(tmpv);
00609 cycloid_midpoint(tmpv, 0.8, start, via_goal, tmpheight);
00610 cycloid_path.push_back(tmpv);
00611 cycloid_path.push_back(via_goal);
00612 cycloid_path.push_back(goal);
00613 return calc_antecedent_path_base(cycloid_path);
00614 };
00615 };
00616
00617 class cycloid_delay_kick_hoffarbib_trajectory_generator : public delay_hoffarbib_trajectory_generator
00618 {
00619 private:
00620 hrp::Matrix33 start_rot;
00621 hrp::Vector3 kick_point_offset;
00622 public:
00623 cycloid_delay_kick_hoffarbib_trajectory_generator() : delay_hoffarbib_trajectory_generator(), kick_point_offset(hrp::Vector3(-0.1, 0.0, 0.0)) {};
00624 void set_cycloid_delay_kick_point_offset (const hrp::Vector3 _offset) { kick_point_offset = _offset; };
00625 void set_start_rot (const hrp::Matrix33 _offset) { start_rot = _offset; };
00626 hrp::Vector3 get_cycloid_delay_kick_point_offset () const { return kick_point_offset; };
00627 double calc_antecedent_path (const hrp::Vector3& start, const hrp::Vector3& goal, const double height)
00628 {
00629 std::vector<hrp::Vector3> cycloid_path;
00630 hrp::Vector3 tmpv, via_goal(goal);
00631 double ratio = 0.4;
00632 via_goal(2) += ratio*height;
00633 double tmpheight = ((start(2)+goal(2))/2.0+height-(start(2)+via_goal(2))/2.0);
00634
00635 cycloid_path.push_back(start);
00636 if(height > 1e-4){
00637 cycloid_path.push_back(start + start_rot * kick_point_offset);
00638 cycloid_midpoint(tmpv, 0.2, start + start_rot * kick_point_offset, via_goal, tmpheight);
00639 cycloid_path.push_back(tmpv);
00640 cycloid_midpoint(tmpv, 0.4, start + start_rot * kick_point_offset, via_goal, tmpheight);
00641 cycloid_path.push_back(tmpv);
00642 cycloid_midpoint(tmpv, 0.6, start + start_rot * kick_point_offset, via_goal, tmpheight);
00643 cycloid_path.push_back(tmpv);
00644 cycloid_midpoint(tmpv, 0.8, start + start_rot * kick_point_offset, via_goal, tmpheight);
00645 cycloid_path.push_back(tmpv);
00646 }
00647 cycloid_path.push_back(via_goal);
00648 cycloid_path.push_back(goal);
00649 return calc_antecedent_path_base(cycloid_path);
00650 };
00651 };
00652
00653 class cross_delay_hoffarbib_trajectory_generator : public delay_hoffarbib_trajectory_generator
00654 {
00655 private:
00656 leg_type swing_leg;
00657 public:
00658 cross_delay_hoffarbib_trajectory_generator () : delay_hoffarbib_trajectory_generator(), way_point_offset(hrp::Vector3(0.04, 0.15, 0.0)) {};
00659 ~cross_delay_hoffarbib_trajectory_generator () {};
00660 void set_swing_leg (leg_type _lr) { swing_leg = _lr; };
00661 hrp::Vector3 way_point_offset;
00662 double calc_antecedent_path (const hrp::Vector3& start, const hrp::Vector3& goal, const double height)
00663 {
00664 std::vector<hrp::Vector3> path;
00665 double max_height = std::max(start(2), goal(2))+height;
00666 hrp::Vector3 diff_vec = goal - start;
00667 diff_vec(2) = 0.0;
00668 path.push_back(start);
00669 if ( swing_leg == LLEG ) {
00670 path.push_back(hrp::Vector3(start+-1*way_point_offset(0)*diff_vec.normalized()+hrp::Vector3(0,way_point_offset(1),way_point_offset(2)+max_height-start(2))));
00671 path.push_back(hrp::Vector3(goal+way_point_offset(0)*diff_vec.normalized()+hrp::Vector3(0,way_point_offset(1),way_point_offset(2)+max_height-goal(2))));
00672 } else {
00673 path.push_back(hrp::Vector3(start+-1*way_point_offset(0)*diff_vec.normalized()+hrp::Vector3(0,-way_point_offset(1),way_point_offset(2)+max_height-start(2))));
00674 path.push_back(hrp::Vector3(goal+way_point_offset(0)*diff_vec.normalized()+hrp::Vector3(0,-way_point_offset(1),way_point_offset(2)+max_height-goal(2))));
00675 }
00676 if (height > 30 * 1e-3) {
00677 path.push_back(hrp::Vector3(goal(0), goal(1), 30*1e-3+goal(2)));
00678 }
00679 path.push_back(goal);
00680 return calc_antecedent_path_base(path);
00681 };
00682 };
00683
00684
00685 class leg_coords_generator
00686 {
00687 #ifdef HAVE_MAIN
00688 public:
00689 #endif
00690 std::vector< std::vector<step_node> > swing_leg_dst_steps_list, support_leg_steps_list;
00691
00692 std::vector<step_node> support_leg_steps;
00693
00694 std::vector<step_node> swing_leg_steps, swing_leg_src_steps, swing_leg_dst_steps;
00695 double default_step_height, default_top_ratio, current_step_height, swing_ratio, dt, current_toe_angle, current_heel_angle;
00696 double time_offset, final_distance_weight, time_offset_xy2z;
00697 std::vector<double> current_swing_time;
00698
00699 size_t footstep_index;
00700
00701 size_t lcg_count, one_step_count, next_one_step_count;
00702
00703 std::vector<leg_type> support_leg_types, swing_leg_types;
00704 orbit_type default_orbit_type;
00705 bool is_swing_phase;
00706
00707 std::vector<rectangle_delay_hoffarbib_trajectory_generator> rdtg;
00708 stair_delay_hoffarbib_trajectory_generator sdtg;
00709 std::vector<cycloid_delay_hoffarbib_trajectory_generator> cdtg;
00710 cycloid_delay_kick_hoffarbib_trajectory_generator cdktg;
00711 cross_delay_hoffarbib_trajectory_generator crdtg;
00712 toe_heel_phase_counter thp;
00713 interpolator* foot_midcoords_interpolator;
00714 coordinates swing_support_midcoords;
00715
00716 std::map<leg_type, interpolator*> swing_foot_rot_interpolator;
00717
00718 interpolator* toe_heel_interpolator;
00719 double toe_pos_offset_x, heel_pos_offset_x, toe_angle, heel_angle, foot_dif_rot_angle, toe_heel_dif_angle;
00720 bool use_toe_joint, use_toe_heel_auto_set;
00721 toe_heel_type current_src_toe_heel_type, current_dst_toe_heel_type;
00722 void calc_current_swing_foot_rot (std::map<leg_type, hrp::Vector3>& tmp_swing_foot_rot, const double _default_double_support_ratio_before, const double _default_double_support_ratio_after);
00723 void calc_current_swing_leg_steps (std::vector<step_node>& rets, const double step_height, const double _current_toe_angle, const double _current_heel_angle, const double _default_double_support_ratio_before, const double _default_double_support_ratio_after);
00724 double calc_interpolated_toe_heel_angle (const toe_heel_phase start_phase, const toe_heel_phase goal_phase, const double start, const double goal);
00725 void modif_foot_coords_for_toe_heel_phase (coordinates& org_coords, const double _current_toe_angle, const double _current_heel_angle);
00726 void cycloid_midcoords (coordinates& ret, const coordinates& start,
00727 const coordinates& goal, const double height) const;
00728 void rectangle_midcoords (coordinates& ret, const coordinates& start,
00729 const coordinates& goal, const double height, const size_t swing_trajectory_generator_idx);
00730 void stair_midcoords (coordinates& ret, const coordinates& start,
00731 const coordinates& goal, const double height);
00732 void cycloid_delay_midcoords (coordinates& ret, const coordinates& start,
00733 const coordinates& goal, const double height, const size_t swing_trajectory_generator_idx);
00734 void cycloid_delay_kick_midcoords (coordinates& ret, const coordinates& start,
00735 const coordinates& goal, const double height);
00736 void cross_delay_midcoords (coordinates& ret, const coordinates& start,
00737 const coordinates& goal, const double height, leg_type lr);
00738 void calc_ratio_from_double_support_ratio (const double default_double_support_ratio_before, const double default_double_support_ratio_after);
00739 void calc_swing_support_mid_coords ();
00740 #ifndef HAVE_MAIN
00741 public:
00742 #endif
00743 leg_coords_generator(const double _dt)
00744 : support_leg_steps(), swing_leg_steps(), swing_leg_src_steps(), swing_leg_dst_steps(),
00745 default_step_height(0.05), default_top_ratio(0.5), current_step_height(0.0), swing_ratio(0), dt(_dt),
00746 current_toe_angle(0), current_heel_angle(0),
00747 time_offset(0.35), final_distance_weight(1.0), time_offset_xy2z(0),
00748 footstep_index(0), lcg_count(0), default_orbit_type(CYCLOID),
00749 rdtg(), cdtg(),
00750 thp(),
00751 foot_midcoords_interpolator(NULL), swing_foot_rot_interpolator(), toe_heel_interpolator(NULL),
00752 toe_pos_offset_x(0.0), heel_pos_offset_x(0.0), toe_angle(0.0), heel_angle(0.0), foot_dif_rot_angle(0.0), toe_heel_dif_angle(0.0), use_toe_joint(false), use_toe_heel_auto_set(false),
00753 current_src_toe_heel_type(SOLE), current_dst_toe_heel_type(SOLE)
00754 {
00755 support_leg_types = boost::assign::list_of<leg_type>(RLEG);
00756 swing_leg_types = boost::assign::list_of<leg_type>(LLEG);
00757 current_swing_time = boost::assign::list_of<double>(0.0)(0.0)(0.0)(0.0);
00758 sdtg.set_dt(dt);
00759 cdktg.set_dt(dt);
00760 crdtg.set_dt(dt);
00761 if (foot_midcoords_interpolator == NULL) foot_midcoords_interpolator = new interpolator(6, dt);
00762 std::vector<leg_type> tmp_leg_types = boost::assign::list_of<leg_type>(RLEG)(LLEG)(RARM)(LARM);
00763 for (size_t i = 0; i < tmp_leg_types.size(); i++) {
00764 if ( swing_foot_rot_interpolator.find(tmp_leg_types[i]) == swing_foot_rot_interpolator.end() ) {
00765 swing_foot_rot_interpolator.insert(std::pair<leg_type, interpolator*>(tmp_leg_types[i], new interpolator(3, dt)));
00766 swing_foot_rot_interpolator[tmp_leg_types[i]]->setName("GaitGenerator swing_foot_rot_interpolator " + leg_type_to_leg_type_string(tmp_leg_types[i]));
00767 std::cerr << "GaitGenerator swing_foot_rot_interpolator " + leg_type_to_leg_type_string(tmp_leg_types[i]) << std::endl;;
00768 }
00769 }
00770
00771 if (toe_heel_interpolator == NULL) toe_heel_interpolator = new interpolator(1, dt);
00772 foot_midcoords_interpolator->setName("GaitGenerator foot_midcoords_interpolator");
00773 toe_heel_interpolator->setName("GaitGenerator toe_heel_interpolator");
00774 };
00775 ~leg_coords_generator()
00776 {
00777 if (foot_midcoords_interpolator != NULL) {
00778 delete foot_midcoords_interpolator;
00779 foot_midcoords_interpolator = NULL;
00780 }
00781 for (std::map<leg_type, interpolator*>::iterator it = swing_foot_rot_interpolator.begin(); it != swing_foot_rot_interpolator.end(); it++) {
00782 if (it->second != NULL) {
00783 delete it->second;
00784 it->second = NULL;
00785 }
00786 }
00787 if (toe_heel_interpolator != NULL) {
00788 delete toe_heel_interpolator;
00789 toe_heel_interpolator = NULL;
00790 }
00791 };
00792 void set_default_step_height (const double _tmp) { default_step_height = _tmp; };
00793 void set_default_top_ratio (const double _tmp) { default_top_ratio = _tmp; };
00794 void set_default_orbit_type (const orbit_type _tmp) { default_orbit_type = _tmp; };
00795 void set_swing_trajectory_delay_time_offset (const double _time_offset)
00796 {
00797 sdtg.set_swing_trajectory_delay_time_offset(_time_offset);
00798 cdktg.set_swing_trajectory_delay_time_offset(_time_offset);
00799 crdtg.set_swing_trajectory_delay_time_offset(_time_offset);
00800 time_offset = _time_offset;
00801 };
00802 void set_swing_trajectory_final_distance_weight (const double _final_distance_weight)
00803 {
00804 sdtg.set_swing_trajectory_final_distance_weight(_final_distance_weight);
00805 cdktg.set_swing_trajectory_final_distance_weight(_final_distance_weight);
00806 crdtg.set_swing_trajectory_final_distance_weight(_final_distance_weight);
00807 final_distance_weight = _final_distance_weight;
00808 };
00809 void set_swing_trajectory_time_offset_xy2z (const double _tmp)
00810 {
00811 sdtg.set_swing_trajectory_time_offset_xy2z(_tmp);
00812 cdktg.set_swing_trajectory_time_offset_xy2z(_tmp);
00813 crdtg.set_swing_trajectory_time_offset_xy2z(_tmp);
00814 time_offset_xy2z = _tmp;
00815 };
00816 void set_stair_trajectory_way_point_offset (const hrp::Vector3 _offset) { sdtg.set_stair_trajectory_way_point_offset(_offset); };
00817 void set_cycloid_delay_kick_point_offset (const hrp::Vector3 _offset) { cdktg.set_cycloid_delay_kick_point_offset(_offset); };
00818 void set_toe_pos_offset_x (const double _offx) { toe_pos_offset_x = _offx; };
00819 void set_heel_pos_offset_x (const double _offx) { heel_pos_offset_x = _offx; };
00820 void set_toe_angle (const double _angle) { toe_angle = _angle; };
00821 void set_heel_angle (const double _angle) { heel_angle = _angle; };
00822 void set_use_toe_joint (const bool ut) { use_toe_joint = ut; };
00823 void set_use_toe_heel_auto_set (const bool ut) { use_toe_heel_auto_set = ut; };
00824 void set_swing_support_steps_list (const std::vector< std::vector<step_node> >& fnsl)
00825 {
00826 std::vector<step_node> prev_support_leg_steps = support_leg_steps_list.front();
00827 support_leg_steps_list.clear();
00828 swing_leg_dst_steps_list.clear();
00829 support_leg_steps_list.push_back(prev_support_leg_steps);
00830 swing_leg_dst_steps_list = fnsl;
00831 for (size_t i = 0; i < fnsl.size(); i++) {
00832 if (i > 0) {
00833 if (is_same_footstep_nodes(fnsl.at(i), fnsl.at(i-1))) {
00834 support_leg_steps_list.push_back(support_leg_steps_list.back());
00835 } else {
00836
00837 std::vector<step_node> tmp_support_leg_steps = swing_leg_dst_steps_list.at(i-1);
00838 std::copy(support_leg_steps_list.back().begin(),
00839 support_leg_steps_list.back().end(),
00840 std::back_inserter(tmp_support_leg_steps));
00841 for (size_t j = 0; j < swing_leg_dst_steps_list.at(i).size(); j++) {
00842 std::vector<step_node>::iterator it = std::remove_if(tmp_support_leg_steps.begin(),
00843 tmp_support_leg_steps.end(),
00844 (&boost::lambda::_1->* &step_node::l_r == swing_leg_dst_steps_list.at(i).at(j).l_r));
00845 tmp_support_leg_steps.erase(it, tmp_support_leg_steps.end());
00846 }
00847 support_leg_steps_list.push_back(tmp_support_leg_steps);
00848 }
00849 }
00850 }
00851 };
00852 bool set_toe_heel_phase_ratio (const std::vector<double>& ratio) { return thp.set_toe_heel_phase_ratio(ratio); };
00853 void reset(const size_t _one_step_count, const size_t _next_one_step_count,
00854 const std::vector<step_node>& _swing_leg_dst_steps,
00855 const std::vector<step_node>& _swing_leg_src_steps,
00856 const std::vector<step_node>& _support_leg_steps,
00857 const double default_double_support_ratio_before,
00858 const double default_double_support_ratio_after)
00859 {
00860 support_leg_steps_list.clear();
00861 swing_leg_dst_steps_list.clear();
00862
00863 swing_leg_dst_steps = _swing_leg_dst_steps;
00864 swing_leg_src_steps = _swing_leg_src_steps;
00865 support_leg_steps = _support_leg_steps;
00866 support_leg_steps_list.push_back(support_leg_steps);
00867 one_step_count = lcg_count = _one_step_count;
00868 next_one_step_count = _next_one_step_count;
00869 thp.set_one_step_count(one_step_count);
00870 footstep_index = 0;
00871 current_step_height = 0.0;
00872 switch (default_orbit_type) {
00873 case RECTANGLE:
00874 rdtg.clear();
00875 for (size_t i = 0; i < swing_leg_dst_steps.size(); i++) {
00876 rdtg.push_back(rectangle_delay_hoffarbib_trajectory_generator());
00877 rdtg.back().reset_all(dt, one_step_count,
00878 default_double_support_ratio_before, default_double_support_ratio_after,
00879 time_offset, final_distance_weight, time_offset_xy2z);
00880 }
00881 break;
00882 case STAIR:
00883 sdtg.reset(one_step_count, default_double_support_ratio_before, default_double_support_ratio_after);
00884 break;
00885 case CYCLOIDDELAY:
00886 cdtg.clear();
00887 for (size_t i = 0; i < swing_leg_dst_steps.size(); i++) {
00888 cdtg.push_back(cycloid_delay_hoffarbib_trajectory_generator());
00889 cdtg.back().reset_all(dt, one_step_count,
00890 default_double_support_ratio_before, default_double_support_ratio_after,
00891 time_offset, final_distance_weight, time_offset_xy2z);
00892 }
00893 break;
00894 case CYCLOIDDELAYKICK:
00895 cdktg.reset(one_step_count, default_double_support_ratio_before, default_double_support_ratio_after);
00896 break;
00897 case CROSS:
00898 crdtg.reset(one_step_count, default_double_support_ratio_before, default_double_support_ratio_after);
00899 break;
00900 default:
00901 break;
00902 }
00903 current_src_toe_heel_type = current_dst_toe_heel_type = SOLE;
00904 };
00905 void clear_interpolators ( ) {
00906 double tmpsw[3];
00907 for (std::map<leg_type, interpolator*>::iterator it = swing_foot_rot_interpolator.begin(); it != swing_foot_rot_interpolator.end(); it++) {
00908 while (!it->second->isEmpty()) it->second->get(tmpsw, true);
00909 }
00910 double tmpfm[foot_midcoords_interpolator->dimension()];
00911 while (!foot_midcoords_interpolator->isEmpty()) {
00912 foot_midcoords_interpolator->get(tmpfm, true);
00913 }
00914 double tmp;
00915 while (!toe_heel_interpolator->isEmpty()) {
00916 toe_heel_interpolator->get(&tmp, true);
00917 }
00918 };
00919 bool is_same_footstep_nodes(const std::vector<step_node>& fns_1, const std::vector<step_node>& fns_2) const;
00920 void update_leg_steps (const std::vector< std::vector<step_node> >& fnsl, const double default_double_support_ratio_before, const double default_double_support_ratio_after, const toe_heel_type_checker& thtc);
00921 void calc_swing_leg_src_steps (std::vector<step_node>& ret_swing_leg_src_steps, const std::vector< std::vector<step_node> >& fnsl, const size_t _footstep_index)
00922 {
00923 if (_footstep_index > 0) {
00924 if (is_same_footstep_nodes(fnsl[_footstep_index], fnsl[_footstep_index-1])) {
00925 ret_swing_leg_src_steps = swing_leg_dst_steps_list[_footstep_index-1];
00926 } else {
00927
00928 std::vector<step_node> tmp_swing_leg_src_steps = support_leg_steps_list[_footstep_index-1];
00929 std::copy(swing_leg_dst_steps_list[_footstep_index-1].begin(),
00930 swing_leg_dst_steps_list[_footstep_index-1].end(),
00931 std::back_inserter(tmp_swing_leg_src_steps));
00932 std::vector<step_node> tmp_support_leg_steps = support_leg_steps_list[_footstep_index];
00933 for (size_t i = 0; i < tmp_support_leg_steps.size(); i++) {
00934 std::vector<step_node>::iterator it = std::remove_if(tmp_swing_leg_src_steps.begin(), tmp_swing_leg_src_steps.end(), (&boost::lambda::_1->* &step_node::l_r == tmp_support_leg_steps.at(i).l_r));
00935 tmp_swing_leg_src_steps.erase(it, tmp_swing_leg_src_steps.end());
00936 }
00937 ret_swing_leg_src_steps = tmp_swing_leg_src_steps;
00938 }
00939 }
00940 };
00941 void calc_swing_support_params_from_footstep_nodes_list (const std::vector< std::vector<step_node> >& fnsl)
00942 {
00943
00944 size_t current_footstep_index = (footstep_index < fnsl.size() - 1 ? footstep_index : fnsl.size()-1);
00945 swing_leg_dst_steps = fnsl[current_footstep_index];
00946 if (footstep_index != 0) {
00947 support_leg_steps = support_leg_steps_list[current_footstep_index];
00948 }
00949 support_leg_types.clear();
00950 for (std::vector<step_node>::iterator it = support_leg_steps.begin(); it != support_leg_steps.end(); it++) {
00951 support_leg_types.push_back(it->l_r);
00952 }
00953 swing_leg_types.clear();
00954 for (std::vector<step_node>::iterator it = swing_leg_dst_steps.begin(); it != swing_leg_dst_steps.end(); it++) {
00955 swing_leg_types.push_back(it->l_r);
00956 }
00957 calc_swing_leg_src_steps(swing_leg_src_steps, fnsl, current_footstep_index);
00958 };
00959 size_t get_footstep_index() const { return footstep_index; };
00960 size_t get_lcg_count() const { return lcg_count; };
00961 double get_current_swing_time(const size_t idx) const { return current_swing_time.at(idx); };
00962 const std::vector<step_node>& get_swing_leg_steps() const { return swing_leg_steps; };
00963 const std::vector<step_node>& get_support_leg_steps() const { return support_leg_steps; };
00964 const std::vector<step_node>& get_swing_leg_src_steps() const { return swing_leg_src_steps; };
00965 const std::vector<step_node>& get_swing_leg_dst_steps() const { return swing_leg_dst_steps; };
00966 const std::vector<step_node>& get_swing_leg_dst_steps_idx(const size_t idx) const { return swing_leg_dst_steps_list[idx]; };
00967 const std::vector<step_node>& get_support_leg_steps_idx(const size_t idx) const { return support_leg_steps_list[idx]; };
00968 const std::vector<leg_type>& get_support_leg_types() const { return support_leg_types;};
00969 const std::vector<leg_type>& get_swing_leg_types() const { return swing_leg_types;};
00970 double get_default_step_height () const { return default_step_height;};
00971 void get_swing_support_mid_coords(coordinates& ret) const
00972 {
00973 ret = swing_support_midcoords;
00974 };
00975 std::vector<leg_type> get_current_support_states () const
00976 {
00977 if ( is_swing_phase ) {
00978 return get_support_leg_types();
00979 } else {
00980 std::vector<leg_type> tmp_sup_types = get_support_leg_types();
00981 std::vector<leg_type> tmp_swg_types = get_swing_leg_types();
00982 std::copy(tmp_swg_types.begin(), tmp_swg_types.end(), std::back_inserter(tmp_sup_types));
00983 return tmp_sup_types;
00984 }
00985 };
00986 orbit_type get_default_orbit_type () const { return default_orbit_type; };
00987 double get_swing_trajectory_delay_time_offset () const { return time_offset; };
00988 double get_swing_trajectory_final_distance_weight () const { return final_distance_weight; };
00989 double get_swing_trajectory_time_offset_xy2z () const { return time_offset_xy2z; };
00990 hrp::Vector3 get_stair_trajectory_way_point_offset () const { return sdtg.get_stair_trajectory_way_point_offset(); };
00991 hrp::Vector3 get_cycloid_delay_kick_point_offset () const { return cdktg.get_cycloid_delay_kick_point_offset() ; };
00992 double get_toe_pos_offset_x () const { return toe_pos_offset_x; };
00993 double get_heel_pos_offset_x () const { return heel_pos_offset_x; };
00994 double get_toe_angle () const { return toe_angle; };
00995 double get_heel_angle () const { return heel_angle; };
00996 double get_foot_dif_rot_angle () const { return foot_dif_rot_angle; };
00997 bool get_use_toe_joint () const { return use_toe_joint; };
00998 bool get_use_toe_heel_auto_set () const { return use_toe_heel_auto_set; };
00999 void get_toe_heel_phase_ratio (std::vector<double>& ratio) const { thp.get_toe_heel_phase_ratio(ratio); };
01000 double get_current_toe_heel_ratio (const bool _use_toe_heel_transition) const
01001 {
01002 if (_use_toe_heel_transition && current_step_height > 0.0) {
01003 return thp.calc_phase_ratio_for_toe_heel_transition(one_step_count - lcg_count);
01004 } else {
01005 return no_using_toe_heel_ratio;
01006 }
01007 };
01008 #ifdef FOR_TESTGAITGENERATOR
01009 size_t get_one_step_count() const { return one_step_count; };
01010 double get_toe_heel_dif_angle() const { return toe_heel_dif_angle; };
01011 #endif // FOR_TESTGAITGENERATOR
01012 };
01013
01014 class gait_generator
01015 {
01016
01017 public:
01018 #ifndef HAVE_MAIN
01019 private:
01020 #endif
01021
01022 enum velocity_mode_flag { VEL_IDLING, VEL_DOING, VEL_ENDING };
01023 enum emergency_flag { IDLING, EMERGENCY_STOP, STOPPING };
01024
01025
01026
01027
01028 std::vector< std::vector<step_node> > footstep_nodes_list;
01029
01030 std::vector< std::vector<step_node> > overwrite_footstep_nodes_list;
01031 refzmp_generator rg;
01032 leg_coords_generator lcg;
01033 footstep_parameter footstep_param;
01034 velocity_mode_parameter vel_param, offset_vel_param;
01035 toe_heel_type_checker thtc;
01036 hrp::Vector3 cog, refzmp, prev_que_rzmp;
01037 std::vector<hrp::Vector3> swing_foot_zmp_offsets, prev_que_sfzos;
01038 double dt;
01039 std::vector<std::string> all_limbs;
01040 double default_step_time;
01041 double default_double_support_ratio_before, default_double_support_ratio_after, default_double_support_static_ratio_before, default_double_support_static_ratio_after;
01042 double default_double_support_ratio_swing_before;
01043 double default_double_support_ratio_swing_after;
01044 double gravitational_acceleration;
01045 size_t finalize_count, optional_go_pos_finalize_footstep_num;
01046
01047
01048 size_t overwrite_footstep_index;
01049
01050
01051 size_t overwritable_footstep_index_offset;
01052 velocity_mode_flag velocity_mode_flg;
01053 emergency_flag emergency_flg;
01054 bool use_inside_step_limitation;
01055 std::map<leg_type, std::string> leg_type_map;
01056 coordinates initial_foot_mid_coords;
01057 bool solved;
01058 double leg_margin[4], stride_limitation_for_circle_type[5], overwritable_stride_limitation[5], footstep_modification_gain, cp_check_margin[2], margin_time_ratio;
01059 bool use_stride_limitation, is_emergency_walking[2], modify_footsteps;
01060 hrp::Vector3 diff_cp, modified_d_footstep;
01061 std::vector<bool> act_contact_states;
01062 stride_limitation_type default_stride_limitation_type;
01063
01064
01065
01066 preview_dynamics_filter<extended_preview_control>* preview_controller_ptr;
01067
01068 void append_go_pos_step_nodes (const coordinates& _ref_coords,
01069 const std::vector<leg_type>& lts)
01070 {
01071 append_go_pos_step_nodes(_ref_coords, lts, footstep_nodes_list);
01072 };
01073
01074 void append_go_pos_step_nodes (const coordinates& _ref_coords,
01075 const std::vector<leg_type>& lts,
01076 std::vector< std::vector<step_node> >& _footstep_nodes_list) const
01077 {
01078 std::vector<step_node> sns;
01079 for (size_t i = 0; i < lts.size(); i++) {
01080 sns.push_back(step_node(lts.at(i), _ref_coords,
01081 lcg.get_default_step_height(), default_step_time,
01082 lcg.get_toe_angle(), lcg.get_heel_angle()));
01083 sns.at(i).worldcoords.pos += sns.at(i).worldcoords.rot * footstep_param.leg_default_translate_pos[lts.at(i)];
01084 }
01085 _footstep_nodes_list.push_back(sns);
01086 };
01087 void overwrite_refzmp_queue(const std::vector< std::vector<step_node> >& fnsl);
01088 void calc_ref_coords_trans_vector_velocity_mode (coordinates& ref_coords, hrp::Vector3& trans, double& dth, const std::vector<step_node>& sup_fns, const velocity_mode_parameter& cur_vel_param) const;
01089 void calc_next_coords_velocity_mode (std::vector< std::vector<step_node> >& ret_list, const size_t idx, const size_t future_step_num = 3);
01090 void append_footstep_list_velocity_mode ();
01091 void append_footstep_list_velocity_mode (std::vector< std::vector<step_node> >& _footstep_nodes_list, const velocity_mode_parameter& cur_vel_param) const;
01092 inline leg_type get_leg_type_from_ee_name (const std::string& ee_name) const
01093 {
01094 return std::find_if(leg_type_map.begin(), leg_type_map.end(), (&boost::lambda::_1->* &std::map<leg_type, std::string>::value_type::second == ee_name))->first;
01095 };
01096
01097 #ifndef HAVE_MAIN
01098
01099 gait_generator (const gait_generator& _p);
01100 gait_generator &operator=(const gait_generator &_p);
01101 public:
01102 #endif
01103 gait_generator (double _dt,
01104
01105 const std::vector<hrp::Vector3>& _leg_pos, std::vector<std::string> _all_limbs,
01106 const double _stride_fwd_x, const double _stride_outside_y, const double _stride_outside_theta,
01107 const double _stride_bwd_x, const double _stride_inside_y, const double _stride_inside_theta)
01108 : footstep_nodes_list(), overwrite_footstep_nodes_list(), rg(_dt), lcg(_dt),
01109 footstep_param(_leg_pos, _stride_fwd_x, _stride_outside_y, _stride_outside_theta, _stride_bwd_x, _stride_inside_y, _stride_inside_theta),
01110 vel_param(), offset_vel_param(), thtc(), cog(hrp::Vector3::Zero()), refzmp(hrp::Vector3::Zero()), prev_que_rzmp(hrp::Vector3::Zero()), diff_cp(hrp::Vector3::Zero()), modified_d_footstep(hrp::Vector3::Zero()),
01111 dt(_dt), all_limbs(_all_limbs), default_step_time(1.0), default_double_support_ratio_before(0.1), default_double_support_ratio_after(0.1), default_double_support_static_ratio_before(0.0), default_double_support_static_ratio_after(0.0), default_double_support_ratio_swing_before(0.1), default_double_support_ratio_swing_after(0.1), gravitational_acceleration(DEFAULT_GRAVITATIONAL_ACCELERATION),
01112 finalize_count(0), optional_go_pos_finalize_footstep_num(0), overwrite_footstep_index(0), overwritable_footstep_index_offset(1),
01113 velocity_mode_flg(VEL_IDLING), emergency_flg(IDLING), margin_time_ratio(0.01), footstep_modification_gain(5e-6),
01114 use_inside_step_limitation(true), use_stride_limitation(false), modify_footsteps(false), default_stride_limitation_type(SQUARE),
01115 preview_controller_ptr(NULL) {
01116 swing_foot_zmp_offsets = boost::assign::list_of<hrp::Vector3>(hrp::Vector3::Zero());
01117 prev_que_sfzos = boost::assign::list_of<hrp::Vector3>(hrp::Vector3::Zero());
01118 leg_type_map = boost::assign::map_list_of<leg_type, std::string>(RLEG, "rleg")(LLEG, "lleg")(RARM, "rarm")(LARM, "larm");
01119 for (size_t i = 0; i < 4; i++) leg_margin[i] = 0.1;
01120 for (size_t i = 0; i < 5; i++) stride_limitation_for_circle_type[i] = 0.2;
01121 for (size_t i = 0; i < 5; i++) overwritable_stride_limitation[i] = 0.2;
01122 for (size_t i = 0; i < 2; i++) is_emergency_walking[i] = false;
01123 for (size_t i = 0; i < 2; i++) cp_check_margin[i] = 0.025;
01124 };
01125 ~gait_generator () {
01126 if ( preview_controller_ptr != NULL ) {
01127 delete preview_controller_ptr;
01128 preview_controller_ptr = NULL;
01129 }
01130 };
01131 void initialize_gait_parameter (const hrp::Vector3& cog,
01132 const std::vector<step_node>& initial_support_leg_steps,
01133 const std::vector<step_node>& initial_swing_leg_dst_steps,
01134 const double delay = 1.6);
01135 bool proc_one_tick ();
01136 void limit_stride (step_node& cur_fs, const step_node& prev_fs, const double (&limit)[5]) const;
01137 void modify_footsteps_for_recovery ();
01138 void append_footstep_nodes (const std::vector<std::string>& _legs, const std::vector<coordinates>& _fss)
01139 {
01140 std::vector<step_node> tmp_sns;
01141 for (size_t i = 0; i < _legs.size(); i++) {
01142 tmp_sns.push_back(step_node(_legs[i], _fss[i], lcg.get_default_step_height(), default_step_time, lcg.get_toe_angle(), lcg.get_heel_angle()));
01143 }
01144 footstep_nodes_list.push_back(tmp_sns);
01145 };
01146 void append_footstep_nodes (const std::vector<std::string>& _legs, const std::vector<coordinates>& _fss, const double _step_height, const double _step_time, const double _toe_angle, const double _heel_angle)
01147 {
01148 std::vector<step_node> tmp_sns;
01149 for (size_t i = 0; i < _legs.size(); i++) {
01150 tmp_sns.push_back(step_node(_legs[i], _fss[i], _step_height, _step_time, _toe_angle, _heel_angle));
01151 }
01152 footstep_nodes_list.push_back(tmp_sns);
01153 };
01154 void clear_footstep_nodes_list () {
01155 footstep_nodes_list.clear();
01156 overwrite_footstep_nodes_list.clear();
01157 overwrite_footstep_index = 0;
01158 };
01159 bool go_pos_param_2_footstep_nodes_list (const double goal_x, const double goal_y, const double goal_theta,
01160 const std::vector<coordinates>& initial_support_legs_coords, coordinates start_ref_coords,
01161 const std::vector<leg_type>& initial_support_legs,
01162 const bool is_initialize = true) {
01163 std::vector< std::vector<step_node> > new_footstep_nodes_list;
01164 return go_pos_param_2_footstep_nodes_list (goal_x, goal_y, goal_theta,
01165 initial_support_legs_coords, start_ref_coords,
01166 initial_support_legs,
01167 new_footstep_nodes_list,
01168 is_initialize);
01169 };
01170 bool go_pos_param_2_footstep_nodes_list (const double goal_x, const double goal_y, const double goal_theta,
01171 const std::vector<coordinates>& initial_support_legs_coords, coordinates start_ref_coords,
01172 const std::vector<leg_type>& initial_support_legs,
01173 std::vector< std::vector<step_node> >& new_footstep_nodes_list,
01174 const bool is_initialize = true);
01175 void go_pos_param_2_footstep_nodes_list_core (const double goal_x, const double goal_y, const double goal_theta,
01176 const std::vector<coordinates>& initial_support_legs_coords, coordinates start_ref_coords,
01177 const std::vector<leg_type>& initial_support_legs,
01178 std::vector< std::vector<step_node> >& new_footstep_nodes_list,
01179 const bool is_initialize, const size_t overwritable_fs_index) const;
01180 void go_single_step_param_2_footstep_nodes_list (const double goal_x, const double goal_y, const double goal_z, const double goal_theta,
01181 const std::string& tmp_swing_leg,
01182 const coordinates& _support_leg_coords);
01183 void initialize_velocity_mode (const coordinates& _ref_coords,
01184 const double vel_x, const double vel_y, const double vel_theta,
01185 const std::vector<leg_type>& current_legs);
01186 void finalize_velocity_mode ();
01187 void append_finalize_footstep ()
01188 {
01189 append_finalize_footstep(footstep_nodes_list);
01190 };
01191 void append_finalize_footstep (std::vector< std::vector<step_node> >& _footstep_nodes_list) const
01192 {
01193 std::vector<step_node> sns = _footstep_nodes_list[_footstep_nodes_list.size()-2];
01194 for (size_t i = 0; i < sns.size(); i++) {
01195 sns.at(i).step_height = sns.at(i).toe_angle = sns.at(i).heel_angle = 0.0;
01196 }
01197 _footstep_nodes_list.push_back(sns);
01198 };
01199 void emergency_stop ()
01200 {
01201 if (!footstep_nodes_list.empty()) {
01202 velocity_mode_flg = VEL_IDLING;
01203 emergency_flg = EMERGENCY_STOP;
01204 }
01205 };
01206
01207 void set_default_step_time (const double _default_step_time) { default_step_time = _default_step_time; };
01208 void set_default_double_support_ratio_before (const double _default_double_support_ratio_before) { default_double_support_ratio_before = _default_double_support_ratio_before; };
01209 void set_default_double_support_ratio_after (const double _default_double_support_ratio_after) { default_double_support_ratio_after = _default_double_support_ratio_after; };
01210 void set_default_double_support_static_ratio_before (const double _default_double_support_static_ratio_before) { default_double_support_static_ratio_before = _default_double_support_static_ratio_before; };
01211 void set_default_double_support_static_ratio_after (const double _default_double_support_static_ratio_after) { default_double_support_static_ratio_after = _default_double_support_static_ratio_after; };
01212 void set_default_double_support_ratio_swing_before (const double _default_double_support_ratio_swing_before) { default_double_support_ratio_swing_before = _default_double_support_ratio_swing_before; };
01213 void set_default_double_support_ratio_swing_after (const double _default_double_support_ratio_swing_after) { default_double_support_ratio_swing_after = _default_double_support_ratio_swing_after; };
01214 void set_default_zmp_offsets(const std::vector<hrp::Vector3>& tmp) { rg.set_default_zmp_offsets(tmp); };
01215 void set_toe_zmp_offset_x (const double _off) { rg.set_toe_zmp_offset_x(_off); };
01216 void set_heel_zmp_offset_x (const double _off) { rg.set_heel_zmp_offset_x(_off); };
01217 void set_use_toe_heel_transition (const bool _u) { rg.set_use_toe_heel_transition(_u); };
01218 void set_use_toe_heel_auto_set (const bool _u) { rg.set_use_toe_heel_auto_set(_u); lcg.set_use_toe_heel_auto_set(_u); };
01219 void set_zmp_weight_map (const std::map<leg_type, double> _map) { rg.set_zmp_weight_map(_map); };
01220 void set_default_step_height(const double _tmp) { lcg.set_default_step_height(_tmp); };
01221 void set_default_top_ratio(const double _tmp) { lcg.set_default_top_ratio(_tmp); };
01222 void set_velocity_param (const double vel_x, const double vel_y, const double vel_theta)
01223 {
01224 vel_param.set(vel_x, vel_y, vel_theta);
01225 };
01226 void set_offset_velocity_param (const double vel_x, const double vel_y, const double vel_theta)
01227 {
01228 offset_vel_param.set(vel_x, vel_y, vel_theta);
01229 };
01230 void set_stride_parameters (const double _stride_fwd_x, const double _stride_outside_y, const double _stride_outside_theta,
01231 const double _stride_bwd_x, const double _stride_inside_y, const double _stride_inside_theta)
01232 {
01233 footstep_param.stride_fwd_x = _stride_fwd_x;
01234 footstep_param.stride_outside_y = _stride_outside_y;
01235 footstep_param.stride_outside_theta = _stride_outside_theta;
01236 footstep_param.stride_bwd_x = _stride_bwd_x;
01237 footstep_param.stride_inside_y = _stride_inside_y;
01238 footstep_param.stride_inside_theta = _stride_inside_theta;
01239 };
01240 void set_use_inside_step_limitation(const bool uu) { use_inside_step_limitation = uu; };
01241 void set_default_orbit_type (const orbit_type type) { lcg.set_default_orbit_type(type); };
01242 void set_swing_trajectory_delay_time_offset (const double _time_offset) { lcg.set_swing_trajectory_delay_time_offset(_time_offset); };
01243 void set_swing_trajectory_final_distance_weight (const double _final_distance_weight) { lcg.set_swing_trajectory_final_distance_weight(_final_distance_weight); };
01244 void set_swing_trajectory_time_offset_xy2z (const double _tmp) { lcg.set_swing_trajectory_time_offset_xy2z(_tmp); };
01245 void set_stair_trajectory_way_point_offset (const hrp::Vector3 _offset) { lcg.set_stair_trajectory_way_point_offset(_offset); };
01246 void set_cycloid_delay_kick_point_offset (const hrp::Vector3 _offset) { lcg.set_cycloid_delay_kick_point_offset(_offset); };
01247 void set_gravitational_acceleration (const double ga) { gravitational_acceleration = ga; };
01248 void set_toe_pos_offset_x (const double _offx) { lcg.set_toe_pos_offset_x(_offx); };
01249 void set_heel_pos_offset_x (const double _offx) { lcg.set_heel_pos_offset_x(_offx); };
01250 void set_toe_angle (const double _angle) { lcg.set_toe_angle(_angle); };
01251 void set_heel_angle (const double _angle) { lcg.set_heel_angle(_angle); };
01252 bool set_toe_heel_phase_ratio (const std::vector<double>& ratio)
01253 {
01254 bool lcgret = lcg.set_toe_heel_phase_ratio(ratio);
01255 bool rgret = rg.set_toe_heel_phase_ratio(ratio);
01256 return lcgret && rgret;
01257 };
01258 void set_use_toe_joint (const bool ut) { lcg.set_use_toe_joint(ut); };
01259 void set_leg_default_translate_pos (const std::vector<hrp::Vector3>& off) { footstep_param.leg_default_translate_pos = off;};
01260 void set_optional_go_pos_finalize_footstep_num (const size_t num) { optional_go_pos_finalize_footstep_num = num; };
01261 void set_all_limbs (const std::vector<std::string>& _all_limbs) { all_limbs = _all_limbs; };
01262 void set_overwritable_footstep_index_offset (const size_t _of) { overwritable_footstep_index_offset = _of;};
01263 void set_foot_steps_list (const std::vector< std::vector<step_node> >& fnsl)
01264 {
01265 clear_footstep_nodes_list();
01266 footstep_nodes_list = fnsl;
01267 append_finalize_footstep();
01268 print_footstep_nodes_list();
01269 };
01270 void set_overwrite_foot_steps_list (const std::vector< std::vector<step_node> >& fnsl)
01271 {
01272 overwrite_footstep_nodes_list.clear();
01273 overwrite_footstep_nodes_list = fnsl;
01274 append_finalize_footstep(overwrite_footstep_nodes_list);
01275 print_footstep_nodes_list(overwrite_footstep_nodes_list);
01276 };
01277 void set_leg_margin (const double _leg_margin[4]) {
01278 for (size_t i = 0; i < 4; i++) {
01279 leg_margin[i] = _leg_margin[i];
01280 }
01281 };
01282 void set_stride_limitation_for_circle_type (const double (&_stride_limitation_for_circle_type)[5]) {
01283 for (size_t i = 0; i < 5; i++) {
01284 stride_limitation_for_circle_type[i] = _stride_limitation_for_circle_type[i];
01285 }
01286 };
01287 void set_overwritable_stride_limitation (const double (&_overwritable_stride_limitation)[5]) {
01288 for (size_t i = 0; i < 5; i++) {
01289 overwritable_stride_limitation[i] = _overwritable_stride_limitation[i];
01290 }
01291 };
01292 void set_footstep_modification_gain (const double _footstep_modification_gain) { footstep_modification_gain = _footstep_modification_gain; };
01293 void set_cp_check_margin (const double (&_cp_check_margin)[2]) {
01294 for (size_t i=0; i < 2; i++) {
01295 cp_check_margin[i] = _cp_check_margin[i];
01296 }
01297 };
01298 void set_act_contact_states (const std::vector<bool>& _act_contact_states) {
01299 if (act_contact_states.empty()) act_contact_states.resize(_act_contact_states.size());
01300 for (size_t i = 0; i < act_contact_states.size(); i++) {
01301 act_contact_states[i] = _act_contact_states[i];
01302 }
01303 };
01304 void set_use_stride_limitation (const bool _use_stride_limitation) { use_stride_limitation = _use_stride_limitation; };
01305 void set_modify_footsteps (const bool _modify_footsteps) { modify_footsteps = _modify_footsteps; };
01306 void set_margin_time_ratio (const double _margin_time_ratio) { margin_time_ratio = _margin_time_ratio; };
01307 void set_diff_cp (const hrp::Vector3 _cp) { diff_cp = _cp; };
01308 void set_stride_limitation_type (const stride_limitation_type _tmp) { default_stride_limitation_type = _tmp; };
01309 void set_toe_check_thre (const double _a) { thtc.set_toe_check_thre(_a); };
01310 void set_heel_check_thre (const double _a) { thtc.set_heel_check_thre(_a); };
01311
01312 size_t get_overwritable_index () const
01313 {
01314 return lcg.get_footstep_index()+overwritable_footstep_index_offset;
01315 };
01316 bool set_overwrite_foot_step_index (const size_t idx)
01317 {
01318 if (idx >= get_overwritable_index()) {
01319 overwrite_footstep_index = idx;
01320 return true;
01321 } else {
01322 return false;
01323 }
01324 };
01325 bool get_footstep_nodes_by_index (std::vector<step_node>& csl, const size_t idx) const
01326 {
01327 if (footstep_nodes_list.size()-1 >= idx) {
01328 csl = footstep_nodes_list.at(idx);
01329 return true;
01330 } else {
01331 return false;
01332 }
01333 };
01334 void print_footstep_nodes_list (const std::vector< std::vector<step_node> > _footstep_nodes_list) const
01335 {
01336 for (size_t i = 0; i < _footstep_nodes_list.size(); i++) {
01337 for (size_t j = 0; j < _footstep_nodes_list.at(i).size(); j++) {
01338 std::cerr << "[" << i << "] " << _footstep_nodes_list.at(i).at(j) << std::endl;
01339 }
01340 }
01341 };
01342 void print_footstep_nodes_list () const
01343 {
01344 print_footstep_nodes_list(footstep_nodes_list);
01345 };
01346
01347 const hrp::Vector3& get_cog () const { return cog; };
01348 hrp::Vector3 get_cog_vel () const {
01349 double refcog_vel[3];
01350 preview_controller_ptr->get_refcog_vel(refcog_vel);
01351 return hrp::Vector3(refcog_vel[0], refcog_vel[1], refcog_vel[2]);
01352 };
01353 hrp::Vector3 get_cog_acc () const {
01354 double refcog_acc[3];
01355 preview_controller_ptr->get_refcog_acc(refcog_acc);
01356 return hrp::Vector3(refcog_acc[0], refcog_acc[1], refcog_acc[2]);
01357 };
01358 const hrp::Vector3& get_refzmp () const { return refzmp;};
01359 hrp::Vector3 get_cart_zmp () const
01360 {
01361 double czmp[3];
01362 preview_controller_ptr->get_cart_zmp(czmp);
01363 return hrp::Vector3(czmp[0], czmp[1], czmp[2]);
01364 };
01365 std::vector<std::string> convert_leg_types_to_names (const std::vector<leg_type>& lts) const {
01366 std::vector<std::string> ret;
01367 for (std::vector<leg_type>::const_iterator it = lts.begin(); it != lts.end(); it++) {
01368 ret.push_back(leg_type_map.find(*it)->second);
01369 }
01370 return ret;
01371 };
01372 const std::vector<hrp::Vector3>& get_swing_foot_zmp_offsets () const { return swing_foot_zmp_offsets;};
01373 std::vector<hrp::Vector3> get_support_foot_zmp_offsets () const {
01374 std::vector<hrp::Vector3> ret;
01375 for (size_t i = 0; i < lcg.get_support_leg_types().size(); i++) {
01376 ret.push_back(rg.get_default_zmp_offset(lcg.get_support_leg_types().at(i)));
01377 }
01378 return ret;
01379 };
01380
01381 bool get_swing_support_foot_zmp_offsets_from_ee_name (hrp::Vector3& ret, const std::string& ee_name) const
01382 {
01383 leg_type lt = get_leg_type_from_ee_name(ee_name);
01384 std::vector<leg_type>::const_iterator it = std::find(lcg.get_support_leg_types().begin(), lcg.get_support_leg_types().end(), lt);
01385 if (it != lcg.get_support_leg_types().end()) {
01386 ret = get_support_foot_zmp_offsets()[std::distance(lcg.get_support_leg_types().begin(), it)];
01387 } else {
01388 it = std::find(lcg.get_swing_leg_types().begin(), lcg.get_swing_leg_types().end(), lt);
01389 if (it != lcg.get_swing_leg_types().end()) {
01390 ret = get_swing_foot_zmp_offsets()[std::distance(lcg.get_swing_leg_types().begin(), it)];
01391 } else {
01392 return false;
01393 }
01394 }
01395 return true;
01396 };
01397 double get_toe_zmp_offset_x () const { return rg.get_toe_zmp_offset_x(); };
01398 double get_heel_zmp_offset_x () const { return rg.get_heel_zmp_offset_x(); };
01399 bool get_use_toe_heel_transition () const { return rg.get_use_toe_heel_transition(); };
01400 bool get_use_toe_heel_auto_set () const { return rg.get_use_toe_heel_auto_set(); };
01401 const std::map<leg_type, double> get_zmp_weight_map () const { return rg.get_zmp_weight_map(); };
01402 void proc_zmp_weight_map_interpolation () { return rg.proc_zmp_weight_map_interpolation(); };
01403 std::vector<std::string> get_footstep_front_leg_names () const {
01404 std::vector<leg_type> lts;
01405 for (size_t i = 0; i < footstep_nodes_list[0].size(); i++) {
01406 lts.push_back(footstep_nodes_list[0].at(i).l_r);
01407 }
01408 return convert_leg_types_to_names(lts);
01409 };
01410 std::vector<std::string> get_footstep_back_leg_names () const {
01411 std::vector<leg_type> lts;
01412 for (size_t i = 0; i < footstep_nodes_list.back().size(); i++) {
01413 lts.push_back(footstep_nodes_list.back().at(i).l_r);
01414 }
01415 return convert_leg_types_to_names(lts);
01416 };
01417 const std::vector<std::string> get_support_leg_names() const { return convert_leg_types_to_names(lcg.get_support_leg_types());};
01418 const std::vector<std::string> get_swing_leg_names() const { return convert_leg_types_to_names(lcg.get_swing_leg_types());};
01419 const std::vector<step_node>& get_swing_leg_steps() const { return lcg.get_swing_leg_steps(); };
01420 const std::vector<step_node>& get_support_leg_steps() const { return lcg.get_support_leg_steps(); };
01421 const std::vector<step_node>& get_swing_leg_src_steps() const { return lcg.get_swing_leg_src_steps(); };
01422 const std::vector<step_node>& get_swing_leg_dst_steps() const { return lcg.get_swing_leg_dst_steps(); };
01423 const coordinates get_dst_foot_midcoords() const
01424 {
01425 coordinates tmp(lcg.get_swing_leg_dst_steps().front().worldcoords);
01426 tmp.pos += tmp.rot * hrp::Vector3(-1*footstep_param.leg_default_translate_pos[lcg.get_swing_leg_dst_steps().front().l_r]);
01427 return tmp;
01428 };
01429 void get_swing_support_mid_coords(coordinates& ret) const { lcg.get_swing_support_mid_coords(ret); };
01430 void get_stride_parameters (double& _stride_fwd_x, double& _stride_outside_y, double& _stride_outside_theta,
01431 double& _stride_bwd_x, double& _stride_inside_y, double& _stride_inside_theta) const
01432 {
01433 _stride_fwd_x = footstep_param.stride_fwd_x;
01434 _stride_outside_y = footstep_param.stride_outside_y;
01435 _stride_outside_theta = footstep_param.stride_outside_theta;
01436 _stride_bwd_x = footstep_param.stride_bwd_x;
01437 _stride_inside_y = footstep_param.stride_inside_y;
01438 _stride_inside_theta = footstep_param.stride_inside_theta;
01439 };
01440 size_t get_footstep_index() const { return lcg.get_footstep_index(); };
01441 size_t get_lcg_count() const { return lcg.get_lcg_count(); };
01442 double get_current_swing_time(const size_t idx) const { return lcg.get_current_swing_time(idx); };
01443
01444 double get_current_swing_time_from_ee_name (const std::string ee_name) const
01445 {
01446 return get_current_swing_time( get_leg_type_from_ee_name(ee_name) );
01447 };
01448 std::vector<leg_type> get_current_support_states() const { return lcg.get_current_support_states();};
01449 double get_default_step_time () const { return default_step_time; };
01450 double get_default_step_height () const { return lcg.get_default_step_height(); };
01451 double get_default_double_support_ratio_before () const { return default_double_support_ratio_before; };
01452 double get_default_double_support_ratio_after () const { return default_double_support_ratio_after; };
01453 double get_default_double_support_static_ratio_before () const { return default_double_support_static_ratio_before; };
01454 double get_default_double_support_static_ratio_after () const { return default_double_support_static_ratio_after; };
01455 double get_default_double_support_ratio_swing_before () const {return default_double_support_ratio_swing_before; };
01456 double get_default_double_support_ratio_swing_after () const {return default_double_support_ratio_swing_after; };
01457 std::vector< std::vector<step_node> > get_remaining_footstep_nodes_list () const
01458 {
01459 std::vector< std::vector<step_node> > fsnl;
01460 size_t fsl_size = (footstep_nodes_list.size()>lcg.get_footstep_index() ? footstep_nodes_list.size()-lcg.get_footstep_index() : 0);
01461
01462 for (size_t i = 0; i < fsl_size; i++) {
01463 fsnl.push_back(footstep_nodes_list[i+lcg.get_footstep_index()]);
01464 }
01465 return fsnl;
01466 };
01467 orbit_type get_default_orbit_type () const { return lcg.get_default_orbit_type(); };
01468 double get_swing_trajectory_delay_time_offset () const { return lcg.get_swing_trajectory_delay_time_offset(); };
01469 double get_swing_trajectory_final_distance_weight () const { return lcg.get_swing_trajectory_final_distance_weight(); };
01470 double get_swing_trajectory_time_offset_xy2z () const { return lcg.get_swing_trajectory_time_offset_xy2z(); };
01471 hrp::Vector3 get_stair_trajectory_way_point_offset () const { return lcg.get_stair_trajectory_way_point_offset(); };
01472 hrp::Vector3 get_cycloid_delay_kick_point_offset () const { return lcg.get_cycloid_delay_kick_point_offset(); };
01473 double get_gravitational_acceleration () const { return gravitational_acceleration; } ;
01474 double get_toe_pos_offset_x () const { return lcg.get_toe_pos_offset_x(); };
01475 double get_heel_pos_offset_x () const { return lcg.get_heel_pos_offset_x(); };
01476 double get_toe_angle () const { return lcg.get_toe_angle(); };
01477 double get_heel_angle () const { return lcg.get_heel_angle(); };
01478 double get_foot_dif_rot_angle () const { return lcg.get_foot_dif_rot_angle(); };
01479 void get_toe_heel_phase_ratio (std::vector<double>& ratio) const { lcg.get_toe_heel_phase_ratio(ratio); };
01480 int get_NUM_TH_PHASES () const { return NUM_TH_PHASES; };
01481 bool get_use_toe_joint () const { return lcg.get_use_toe_joint(); };
01482 double get_current_toe_heel_ratio () const { return lcg.get_current_toe_heel_ratio(get_use_toe_heel_transition()); };
01483
01484 bool get_current_toe_heel_ratio_from_ee_name (double& ret, const std::string& ee_name) const
01485 {
01486 leg_type lt = get_leg_type_from_ee_name(ee_name);
01487 if (std::find(lcg.get_support_leg_types().begin(), lcg.get_support_leg_types().end(), lt)!=lcg.get_support_leg_types().end()) {
01488 ret = rats::no_using_toe_heel_ratio;
01489 } else if (std::find(lcg.get_swing_leg_types().begin(), lcg.get_support_leg_types().end(), lt)!=lcg.get_swing_leg_types().end()) {
01490 ret = get_current_toe_heel_ratio();
01491 } else {
01492 return false;
01493 }
01494 return true;
01495 };
01496 void get_leg_default_translate_pos (std::vector<hrp::Vector3>& off) const { off = footstep_param.leg_default_translate_pos; };
01497 size_t get_overwritable_footstep_index_offset () const { return overwritable_footstep_index_offset; };
01498 const std::vector<leg_type> calc_counter_leg_types_from_footstep_nodes (const std::vector<step_node>& fns, std::vector<std::string> _all_limbs) const;
01499 const std::map<leg_type, std::string> get_leg_type_map () const { return leg_type_map; };
01500 size_t get_optional_go_pos_finalize_footstep_num () const { return optional_go_pos_finalize_footstep_num; };
01501 bool is_finalizing (const double tm) const { return ((preview_controller_ptr->get_delay()*2 - default_step_time/dt)-finalize_count) <= (tm/dt)-1; };
01502 size_t get_overwrite_check_timing () const { return static_cast<size_t>(footstep_nodes_list[lcg.get_footstep_index()][0].step_time/dt * 0.5) - 1;};
01503 double get_leg_margin (const size_t idx) const { return leg_margin[idx]; };
01504 double get_stride_limitation_for_circle_type (const size_t idx) const { return stride_limitation_for_circle_type[idx]; };
01505 double get_overwritable_stride_limitation (const size_t idx) const { return overwritable_stride_limitation[idx]; };
01506 double get_footstep_modification_gain () const { return footstep_modification_gain; };
01507 double get_cp_check_margin (const size_t idx) const { return cp_check_margin[idx]; };
01508 bool get_modify_footsteps () const { return modify_footsteps; };
01509 double get_margin_time_ratio () const { return margin_time_ratio; };
01510 bool get_use_stride_limitation () const { return use_stride_limitation; };
01511 stride_limitation_type get_stride_limitation_type () const { return default_stride_limitation_type; };
01512 double get_toe_check_thre () const { return thtc.get_toe_check_thre(); };
01513 double get_heel_check_thre () const { return thtc.get_heel_check_thre(); };
01514
01515 bool get_swing_support_ee_coords_from_ee_name (hrp::Vector3& cpos, hrp::Matrix33& crot, const std::string& ee_name) const
01516 {
01517 leg_type lt = get_leg_type_from_ee_name(ee_name);
01518 if (std::find(lcg.get_support_leg_types().begin(), lcg.get_support_leg_types().end(), lt) != lcg.get_support_leg_types().end()) {
01519 coordinates tmpc = std::find_if(lcg.get_support_leg_steps().begin(), lcg.get_support_leg_steps().end(), (&boost::lambda::_1->* &step_node::l_r == lt))->worldcoords;
01520 cpos = tmpc.pos;
01521 crot = tmpc.rot;
01522 } else if (std::find(lcg.get_swing_leg_types().begin(), lcg.get_swing_leg_types().end(), lt) != lcg.get_swing_leg_types().end()) {
01523 coordinates tmpc = std::find_if(lcg.get_swing_leg_steps().begin(), lcg.get_swing_leg_steps().end(), (&boost::lambda::_1->* &step_node::l_r == lt))->worldcoords;
01524 cpos = tmpc.pos;
01525 crot = tmpc.rot;
01526 } else {
01527 return false;
01528 }
01529 return true;
01530 };
01531
01532 bool get_current_support_state_from_ee_name (const std::string& ee_name) const
01533 {
01534 leg_type lt = get_leg_type_from_ee_name(ee_name);
01535 std::vector<leg_type> tmp = lcg.get_current_support_states();
01536 return std::find(tmp.begin(), tmp.end(), lt) != tmp.end();
01537 };
01538 #ifdef FOR_TESTGAITGENERATOR
01539 size_t get_one_step_count() const { return lcg.get_one_step_count(); };
01540 void get_footstep_nodes_list (std::vector< std::vector<step_node> > & fsl) const
01541 {
01542 fsl = footstep_nodes_list;
01543 };
01544 double get_toe_heel_dif_angle () const { return lcg.get_toe_heel_dif_angle(); };
01545 std::vector<hrp::Vector3> get_default_zmp_offsets() const { return rg.get_default_zmp_offsets(); };
01546 #endif // FOR_TESTGAITGENERATOR
01547 void print_param (const std::string& print_str = "") const
01548 {
01549 double stride_fwd_x, stride_outside_y, stride_outside_th, stride_bwd_x, stride_inside_y, stride_inside_th;
01550 get_stride_parameters(stride_fwd_x, stride_outside_y, stride_outside_th, stride_bwd_x, stride_inside_y, stride_inside_th);
01551 std::cerr << "[" << print_str << "] stride_parameter = " << stride_fwd_x << "[m], " << stride_outside_y << "[m], " << stride_outside_th << "[deg], "
01552 << stride_bwd_x << "[m], " << stride_inside_y << "[m], " << stride_inside_th << "[deg]" << std::endl;
01553 std::cerr << "[" << print_str << "] leg_default_translate_pos = ";
01554 for (size_t i = 0; i < footstep_param.leg_default_translate_pos.size(); i++) {
01555 std::cerr << footstep_param.leg_default_translate_pos[i].format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]"));
01556 }
01557 std::cerr << std::endl;
01558 std::cerr << "[" << print_str << "] default_step_time = " << get_default_step_time() << "[s]" << std::endl;
01559 std::cerr << "[" << print_str << "] default_step_height = " << get_default_step_height() << "[m]" << std::endl;
01560 std::cerr << "[" << print_str << "] default_double_support_ratio_before = " << get_default_double_support_ratio_before() << ", default_double_support_ratio_before = " << get_default_double_support_ratio_after() << ", default_double_support_static_ratio_before = " << get_default_double_support_static_ratio_before() << ", default_double_support_static_ratio_after = " << get_default_double_support_static_ratio_after() << ", default_double_support_static_ratio_swing_before = " << get_default_double_support_ratio_swing_before() << ", default_double_support_static_ratio_swing_after = " << get_default_double_support_ratio_swing_after() << std::endl;
01561 std::cerr << "[" << print_str << "] default_orbit_type = ";
01562 if (get_default_orbit_type() == SHUFFLING) {
01563 std::cerr << "SHUFFLING" << std::endl;
01564 } else if (get_default_orbit_type() == CYCLOID) {
01565 std::cerr << "CYCLOID" << std::endl;
01566 } else if (get_default_orbit_type() == RECTANGLE) {
01567 std::cerr << "RECTANGLE" << std::endl;
01568 } else if (get_default_orbit_type() == STAIR) {
01569 std::cerr << "STAIR" << std::endl;
01570 } else if (get_default_orbit_type() == CYCLOIDDELAY) {
01571 std::cerr << "CYCLOIDDELAY" << std::endl;
01572 } else if (get_default_orbit_type() == CYCLOIDDELAYKICK) {
01573 std::cerr << "CYCLOIDDELAYKICK" << std::endl;
01574 } else if (get_default_orbit_type() == CROSS) {
01575 std::cerr << "CROSS" << std::endl;
01576 }
01577 std::cerr << "[" << print_str << "] swing_trajectory_delay_time_offset = " << get_swing_trajectory_delay_time_offset() << "[s], swing_trajectory_final_distance_weight = " << get_swing_trajectory_final_distance_weight()
01578 << ", swing_trajectory_time_offset_xy2z = " << get_swing_trajectory_time_offset_xy2z() << std::endl;
01579 hrp::Vector3 tmpv;
01580 tmpv = get_stair_trajectory_way_point_offset();
01581 std::cerr << "[" << print_str << "] stair_trajectory_way_point_offset = " << tmpv.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]")) << "[m]" << std::endl;
01582 tmpv = get_cycloid_delay_kick_point_offset();
01583 std::cerr << "[" << print_str << "] cycloid_delay_kick_point_offset = " << tmpv.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]")) << "[m]" << std::endl;
01584 std::cerr << "[" << print_str << "] gravitational_acceleration = " << get_gravitational_acceleration() << "[m/s^2]" << std::endl;
01585 std::cerr << "[" << print_str << "] toe_pos_offset_x = " << get_toe_pos_offset_x() << "[mm], heel_pos_offset_x = " << get_heel_pos_offset_x() << "[mm]" << std::endl;
01586 std::cerr << "[" << print_str << "] toe_zmp_offset_x = " << get_toe_zmp_offset_x() << "[mm], heel_zmp_offset_x = " << get_heel_zmp_offset_x() << "[mm]" << std::endl;
01587 std::cerr << "[" << print_str << "] toe_angle = " << get_toe_angle() << "[deg]" << std::endl;
01588 std::cerr << "[" << print_str << "] heel_angle = " << get_heel_angle() << "[deg]" << std::endl;
01589 std::cerr << "[" << print_str << "] use_toe_joint = " << (get_use_toe_joint()?"true":"false") << ", use_toe_heel_transition = " << (get_use_toe_heel_transition()?"true":"false") << ", use_toe_heel_auto_set = " << (get_use_toe_heel_auto_set()?"true":"false") << std::endl;
01590 std::vector<double> tmp_ratio(get_NUM_TH_PHASES(), 0.0);
01591 get_toe_heel_phase_ratio(tmp_ratio);
01592 std::cerr << "[" << print_str << "] toe_heel_phase_ratio = [";
01593 for (int i = 0; i < get_NUM_TH_PHASES(); i++) std::cerr << tmp_ratio[i] << " ";
01594 std::cerr << "]" << std::endl;
01595 std::cerr << "[" << print_str << "] optional_go_pos_finalize_footstep_num = " << optional_go_pos_finalize_footstep_num << ", overwritable_footstep_index_offset = " << overwritable_footstep_index_offset << std::endl;
01596 std::cerr << "[" << print_str << "] default_stride_limitation_type = ";
01597 if (default_stride_limitation_type == SQUARE) {
01598 std::cerr << "SQUARE" << std::endl;
01599 } else if (default_stride_limitation_type == CIRCLE) {
01600 std::cerr << "CIRCLE" << std::endl;
01601 }
01602 thtc.print_param(print_str);
01603 };
01604 };
01605 }
01606 #endif