#include <GaitGenerator.h>
Definition at line 1015 of file GaitGenerator.h.
enum rats::gait_generator::emergency_flag [private] |
Definition at line 1024 of file GaitGenerator.h.
enum rats::gait_generator::velocity_mode_flag [private] |
Definition at line 1023 of file GaitGenerator.h.
rats::gait_generator::gait_generator | ( | const gait_generator & | _p | ) | [private] |
rats::gait_generator::gait_generator | ( | double | _dt, |
const std::vector< hrp::Vector3 > & | _leg_pos, | ||
std::vector< std::string > | _all_limbs, | ||
const double | _stride_fwd_x, | ||
const double | _stride_outside_y, | ||
const double | _stride_outside_theta, | ||
const double | _stride_bwd_x, | ||
const double | _stride_inside_y, | ||
const double | _stride_inside_theta | ||
) | [inline] |
Definition at line 1104 of file GaitGenerator.h.
rats::gait_generator::~gait_generator | ( | ) | [inline] |
Definition at line 1126 of file GaitGenerator.h.
void rats::gait_generator::append_finalize_footstep | ( | ) | [inline] |
Definition at line 1188 of file GaitGenerator.h.
void rats::gait_generator::append_finalize_footstep | ( | std::vector< std::vector< step_node > > & | _footstep_nodes_list | ) | const [inline] |
Definition at line 1192 of file GaitGenerator.h.
void rats::gait_generator::append_footstep_list_velocity_mode | ( | ) | [private] |
Definition at line 1035 of file GaitGenerator.cpp.
void rats::gait_generator::append_footstep_list_velocity_mode | ( | std::vector< std::vector< step_node > > & | _footstep_nodes_list, |
const velocity_mode_parameter & | cur_vel_param | ||
) | const [private] |
Definition at line 1040 of file GaitGenerator.cpp.
void rats::gait_generator::append_footstep_nodes | ( | const std::vector< std::string > & | _legs, |
const std::vector< coordinates > & | _fss | ||
) | [inline] |
Definition at line 1139 of file GaitGenerator.h.
void rats::gait_generator::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 | ||
) | [inline] |
Definition at line 1147 of file GaitGenerator.h.
void rats::gait_generator::append_go_pos_step_nodes | ( | const coordinates & | _ref_coords, |
const std::vector< leg_type > & | lts | ||
) | [inline, private] |
Definition at line 1069 of file GaitGenerator.h.
void rats::gait_generator::append_go_pos_step_nodes | ( | const coordinates & | _ref_coords, |
const std::vector< leg_type > & | lts, | ||
std::vector< std::vector< step_node > > & | _footstep_nodes_list | ||
) | const [inline, private] |
Definition at line 1075 of file GaitGenerator.h.
const std::vector< leg_type > rats::gait_generator::calc_counter_leg_types_from_footstep_nodes | ( | const std::vector< step_node > & | fns, |
std::vector< std::string > | _all_limbs | ||
) | const |
Definition at line 1161 of file GaitGenerator.cpp.
void rats::gait_generator::calc_next_coords_velocity_mode | ( | std::vector< std::vector< step_node > > & | ret_list, |
const size_t | idx, | ||
const size_t | future_step_num = 3 |
||
) | [private] |
Definition at line 1053 of file GaitGenerator.cpp.
void rats::gait_generator::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 [private] |
Definition at line 987 of file GaitGenerator.cpp.
void rats::gait_generator::clear_footstep_nodes_list | ( | ) | [inline] |
Definition at line 1155 of file GaitGenerator.h.
std::vector<std::string> rats::gait_generator::convert_leg_types_to_names | ( | const std::vector< leg_type > & | lts | ) | const [inline] |
Definition at line 1366 of file GaitGenerator.h.
void rats::gait_generator::emergency_stop | ( | ) | [inline] |
Definition at line 1200 of file GaitGenerator.h.
Definition at line 982 of file GaitGenerator.cpp.
hrp::Vector3 rats::gait_generator::get_cart_zmp | ( | ) | const [inline] |
Definition at line 1360 of file GaitGenerator.h.
const hrp::Vector3& rats::gait_generator::get_cog | ( | ) | const [inline] |
Definition at line 1348 of file GaitGenerator.h.
hrp::Vector3 rats::gait_generator::get_cog_acc | ( | ) | const [inline] |
Definition at line 1354 of file GaitGenerator.h.
hrp::Vector3 rats::gait_generator::get_cog_vel | ( | ) | const [inline] |
Definition at line 1349 of file GaitGenerator.h.
double rats::gait_generator::get_cp_check_margin | ( | const size_t | idx | ) | const [inline] |
Definition at line 1508 of file GaitGenerator.h.
bool rats::gait_generator::get_current_support_state_from_ee_name | ( | const std::string & | ee_name | ) | const [inline] |
Definition at line 1533 of file GaitGenerator.h.
std::vector<leg_type> rats::gait_generator::get_current_support_states | ( | ) | const [inline] |
Definition at line 1449 of file GaitGenerator.h.
double rats::gait_generator::get_current_swing_time | ( | const size_t | idx | ) | const [inline] |
Definition at line 1443 of file GaitGenerator.h.
double rats::gait_generator::get_current_swing_time_from_ee_name | ( | const std::string | ee_name | ) | const [inline] |
Definition at line 1445 of file GaitGenerator.h.
double rats::gait_generator::get_current_toe_heel_ratio | ( | ) | const [inline] |
Definition at line 1483 of file GaitGenerator.h.
bool rats::gait_generator::get_current_toe_heel_ratio_from_ee_name | ( | double & | ret, |
const std::string & | ee_name | ||
) | const [inline] |
Definition at line 1485 of file GaitGenerator.h.
hrp::Vector3 rats::gait_generator::get_cycloid_delay_kick_point_offset | ( | ) | const [inline] |
Definition at line 1473 of file GaitGenerator.h.
double rats::gait_generator::get_default_double_support_ratio_after | ( | ) | const [inline] |
Definition at line 1453 of file GaitGenerator.h.
double rats::gait_generator::get_default_double_support_ratio_before | ( | ) | const [inline] |
Definition at line 1452 of file GaitGenerator.h.
double rats::gait_generator::get_default_double_support_ratio_swing_after | ( | ) | const [inline] |
Definition at line 1457 of file GaitGenerator.h.
double rats::gait_generator::get_default_double_support_ratio_swing_before | ( | ) | const [inline] |
Definition at line 1456 of file GaitGenerator.h.
double rats::gait_generator::get_default_double_support_static_ratio_after | ( | ) | const [inline] |
Definition at line 1455 of file GaitGenerator.h.
double rats::gait_generator::get_default_double_support_static_ratio_before | ( | ) | const [inline] |
Definition at line 1454 of file GaitGenerator.h.
orbit_type rats::gait_generator::get_default_orbit_type | ( | ) | const [inline] |
Definition at line 1468 of file GaitGenerator.h.
double rats::gait_generator::get_default_step_height | ( | ) | const [inline] |
Definition at line 1451 of file GaitGenerator.h.
double rats::gait_generator::get_default_step_time | ( | ) | const [inline] |
Definition at line 1450 of file GaitGenerator.h.
const coordinates rats::gait_generator::get_dst_foot_midcoords | ( | ) | const [inline] |
Definition at line 1424 of file GaitGenerator.h.
double rats::gait_generator::get_foot_dif_rot_angle | ( | ) | const [inline] |
Definition at line 1479 of file GaitGenerator.h.
std::vector<std::string> rats::gait_generator::get_footstep_back_leg_names | ( | ) | const [inline] |
Definition at line 1411 of file GaitGenerator.h.
std::vector<std::string> rats::gait_generator::get_footstep_front_leg_names | ( | ) | const [inline] |
Definition at line 1404 of file GaitGenerator.h.
size_t rats::gait_generator::get_footstep_index | ( | ) | const [inline] |
Definition at line 1441 of file GaitGenerator.h.
double rats::gait_generator::get_footstep_modification_gain | ( | ) | const [inline] |
Definition at line 1507 of file GaitGenerator.h.
bool rats::gait_generator::get_footstep_nodes_by_index | ( | std::vector< step_node > & | csl, |
const size_t | idx | ||
) | const [inline] |
Definition at line 1326 of file GaitGenerator.h.
double rats::gait_generator::get_gravitational_acceleration | ( | ) | const [inline] |
Definition at line 1474 of file GaitGenerator.h.
double rats::gait_generator::get_heel_angle | ( | ) | const [inline] |
Definition at line 1478 of file GaitGenerator.h.
double rats::gait_generator::get_heel_check_thre | ( | ) | const [inline] |
Definition at line 1514 of file GaitGenerator.h.
double rats::gait_generator::get_heel_pos_offset_x | ( | ) | const [inline] |
Definition at line 1476 of file GaitGenerator.h.
double rats::gait_generator::get_heel_zmp_offset_x | ( | ) | const [inline] |
Definition at line 1399 of file GaitGenerator.h.
size_t rats::gait_generator::get_lcg_count | ( | ) | const [inline] |
Definition at line 1442 of file GaitGenerator.h.
void rats::gait_generator::get_leg_default_translate_pos | ( | std::vector< hrp::Vector3 > & | off | ) | const [inline] |
Definition at line 1497 of file GaitGenerator.h.
double rats::gait_generator::get_leg_margin | ( | const size_t | idx | ) | const [inline] |
Definition at line 1504 of file GaitGenerator.h.
leg_type rats::gait_generator::get_leg_type_from_ee_name | ( | const std::string & | ee_name | ) | const [inline, private] |
Definition at line 1093 of file GaitGenerator.h.
const std::map<leg_type, std::string> rats::gait_generator::get_leg_type_map | ( | ) | const [inline] |
Definition at line 1500 of file GaitGenerator.h.
double rats::gait_generator::get_margin_time_ratio | ( | ) | const [inline] |
Definition at line 1510 of file GaitGenerator.h.
bool rats::gait_generator::get_modify_footsteps | ( | ) | const [inline] |
Definition at line 1509 of file GaitGenerator.h.
int rats::gait_generator::get_NUM_TH_PHASES | ( | ) | const [inline] |
Definition at line 1481 of file GaitGenerator.h.
size_t rats::gait_generator::get_optional_go_pos_finalize_footstep_num | ( | ) | const [inline] |
Definition at line 1501 of file GaitGenerator.h.
size_t rats::gait_generator::get_overwritable_footstep_index_offset | ( | ) | const [inline] |
Definition at line 1498 of file GaitGenerator.h.
size_t rats::gait_generator::get_overwritable_index | ( | ) | const [inline] |
Definition at line 1313 of file GaitGenerator.h.
double rats::gait_generator::get_overwritable_stride_limitation | ( | const size_t | idx | ) | const [inline] |
Definition at line 1506 of file GaitGenerator.h.
size_t rats::gait_generator::get_overwrite_check_timing | ( | ) | const [inline] |
Definition at line 1503 of file GaitGenerator.h.
const hrp::Vector3& rats::gait_generator::get_refzmp | ( | ) | const [inline] |
Definition at line 1359 of file GaitGenerator.h.
std::vector< std::vector<step_node> > rats::gait_generator::get_remaining_footstep_nodes_list | ( | ) | const [inline] |
Definition at line 1458 of file GaitGenerator.h.
hrp::Vector3 rats::gait_generator::get_stair_trajectory_way_point_offset | ( | ) | const [inline] |
Definition at line 1472 of file GaitGenerator.h.
double rats::gait_generator::get_stride_limitation_for_circle_type | ( | const size_t | idx | ) | const [inline] |
Definition at line 1505 of file GaitGenerator.h.
stride_limitation_type rats::gait_generator::get_stride_limitation_type | ( | ) | const [inline] |
Definition at line 1512 of file GaitGenerator.h.
void rats::gait_generator::get_stride_parameters | ( | double & | _stride_fwd_x, |
double & | _stride_outside_y, | ||
double & | _stride_outside_theta, | ||
double & | _stride_bwd_x, | ||
double & | _stride_inside_y, | ||
double & | _stride_inside_theta | ||
) | const [inline] |
Definition at line 1431 of file GaitGenerator.h.
std::vector<hrp::Vector3> rats::gait_generator::get_support_foot_zmp_offsets | ( | ) | const [inline] |
Definition at line 1374 of file GaitGenerator.h.
const std::vector<std::string> rats::gait_generator::get_support_leg_names | ( | ) | const [inline] |
Definition at line 1418 of file GaitGenerator.h.
const std::vector<step_node>& rats::gait_generator::get_support_leg_steps | ( | ) | const [inline] |
Definition at line 1421 of file GaitGenerator.h.
const std::vector<hrp::Vector3>& rats::gait_generator::get_swing_foot_zmp_offsets | ( | ) | const [inline] |
Definition at line 1373 of file GaitGenerator.h.
const std::vector<step_node>& rats::gait_generator::get_swing_leg_dst_steps | ( | ) | const [inline] |
Definition at line 1423 of file GaitGenerator.h.
const std::vector<std::string> rats::gait_generator::get_swing_leg_names | ( | ) | const [inline] |
Definition at line 1419 of file GaitGenerator.h.
const std::vector<step_node>& rats::gait_generator::get_swing_leg_src_steps | ( | ) | const [inline] |
Definition at line 1422 of file GaitGenerator.h.
const std::vector<step_node>& rats::gait_generator::get_swing_leg_steps | ( | ) | const [inline] |
Definition at line 1420 of file GaitGenerator.h.
bool rats::gait_generator::get_swing_support_ee_coords_from_ee_name | ( | hrp::Vector3 & | cpos, |
hrp::Matrix33 & | crot, | ||
const std::string & | ee_name | ||
) | const [inline] |
Definition at line 1516 of file GaitGenerator.h.
bool rats::gait_generator::get_swing_support_foot_zmp_offsets_from_ee_name | ( | hrp::Vector3 & | ret, |
const std::string & | ee_name | ||
) | const [inline] |
Definition at line 1382 of file GaitGenerator.h.
void rats::gait_generator::get_swing_support_mid_coords | ( | coordinates & | ret | ) | const [inline] |
Definition at line 1430 of file GaitGenerator.h.
double rats::gait_generator::get_swing_trajectory_delay_time_offset | ( | ) | const [inline] |
Definition at line 1469 of file GaitGenerator.h.
double rats::gait_generator::get_swing_trajectory_final_distance_weight | ( | ) | const [inline] |
Definition at line 1470 of file GaitGenerator.h.
double rats::gait_generator::get_swing_trajectory_time_offset_xy2z | ( | ) | const [inline] |
Definition at line 1471 of file GaitGenerator.h.
double rats::gait_generator::get_toe_angle | ( | ) | const [inline] |
Definition at line 1477 of file GaitGenerator.h.
double rats::gait_generator::get_toe_check_thre | ( | ) | const [inline] |
Definition at line 1513 of file GaitGenerator.h.
void rats::gait_generator::get_toe_heel_phase_ratio | ( | std::vector< double > & | ratio | ) | const [inline] |
Definition at line 1480 of file GaitGenerator.h.
double rats::gait_generator::get_toe_pos_offset_x | ( | ) | const [inline] |
Definition at line 1475 of file GaitGenerator.h.
double rats::gait_generator::get_toe_zmp_offset_x | ( | ) | const [inline] |
Definition at line 1398 of file GaitGenerator.h.
bool rats::gait_generator::get_use_stride_limitation | ( | ) | const [inline] |
Definition at line 1511 of file GaitGenerator.h.
bool rats::gait_generator::get_use_toe_heel_auto_set | ( | ) | const [inline] |
Definition at line 1401 of file GaitGenerator.h.
bool rats::gait_generator::get_use_toe_heel_transition | ( | ) | const [inline] |
Definition at line 1400 of file GaitGenerator.h.
bool rats::gait_generator::get_use_toe_joint | ( | ) | const [inline] |
Definition at line 1482 of file GaitGenerator.h.
const std::map<leg_type, double> rats::gait_generator::get_zmp_weight_map | ( | ) | const [inline] |
Definition at line 1402 of file GaitGenerator.h.
bool rats::gait_generator::go_pos_param_2_footstep_nodes_list | ( | const double | goal_x, |
const double | goal_y, | ||
const double | goal_theta, | ||
const std::vector< coordinates > & | initial_support_legs_coords, | ||
coordinates | start_ref_coords, | ||
const std::vector< leg_type > & | initial_support_legs, | ||
const bool | is_initialize = true |
||
) | [inline] |
Definition at line 1160 of file GaitGenerator.h.
bool rats::gait_generator::go_pos_param_2_footstep_nodes_list | ( | const double | goal_x, |
const double | goal_y, | ||
const double | goal_theta, | ||
const std::vector< coordinates > & | initial_support_legs_coords, | ||
coordinates | start_ref_coords, | ||
const std::vector< leg_type > & | initial_support_legs, | ||
std::vector< std::vector< step_node > > & | new_footstep_nodes_list, | ||
const bool | is_initialize = true |
||
) |
Definition at line 843 of file GaitGenerator.cpp.
void rats::gait_generator::go_pos_param_2_footstep_nodes_list_core | ( | const double | goal_x, |
const double | goal_y, | ||
const double | goal_theta, | ||
const std::vector< coordinates > & | initial_support_legs_coords, | ||
coordinates | start_ref_coords, | ||
const std::vector< leg_type > & | initial_support_legs, | ||
std::vector< std::vector< step_node > > & | new_footstep_nodes_list, | ||
const bool | is_initialize, | ||
const size_t | overwritable_fs_index | ||
) | const |
Definition at line 875 of file GaitGenerator.cpp.
void rats::gait_generator::go_single_step_param_2_footstep_nodes_list | ( | const double | goal_x, |
const double | goal_y, | ||
const double | goal_z, | ||
const double | goal_theta, | ||
const std::string & | tmp_swing_leg, | ||
const coordinates & | _support_leg_coords | ||
) |
Definition at line 953 of file GaitGenerator.cpp.
void rats::gait_generator::initialize_gait_parameter | ( | const hrp::Vector3 & | cog, |
const std::vector< step_node > & | initial_support_leg_steps, | ||
const std::vector< step_node > & | initial_swing_leg_dst_steps, | ||
const double | delay = 1.6 |
||
) |
Definition at line 599 of file GaitGenerator.cpp.
void rats::gait_generator::initialize_velocity_mode | ( | const coordinates & | _ref_coords, |
const double | vel_x, | ||
const double | vel_y, | ||
const double | vel_theta, | ||
const std::vector< leg_type > & | current_legs | ||
) |
Definition at line 968 of file GaitGenerator.cpp.
bool rats::gait_generator::is_finalizing | ( | const double | tm | ) | const [inline] |
Definition at line 1502 of file GaitGenerator.h.
void rats::gait_generator::limit_stride | ( | step_node & | cur_fs, |
const step_node & | prev_fs, | ||
const double(&) | limit[5] | ||
) | const |
Definition at line 748 of file GaitGenerator.cpp.
Definition at line 781 of file GaitGenerator.cpp.
gait_generator& rats::gait_generator::operator= | ( | const gait_generator & | _p | ) | [private] |
void rats::gait_generator::overwrite_refzmp_queue | ( | const std::vector< std::vector< step_node > > & | fnsl | ) | [private] |
Definition at line 1084 of file GaitGenerator.cpp.
void rats::gait_generator::print_footstep_nodes_list | ( | const std::vector< std::vector< step_node > > | _footstep_nodes_list | ) | const [inline] |
Definition at line 1335 of file GaitGenerator.h.
void rats::gait_generator::print_footstep_nodes_list | ( | ) | const [inline] |
Definition at line 1343 of file GaitGenerator.h.
void rats::gait_generator::print_param | ( | const std::string & | print_str = "" | ) | const [inline] |
Definition at line 1548 of file GaitGenerator.h.
bool rats::gait_generator::proc_one_tick | ( | ) |
Definition at line 650 of file GaitGenerator.cpp.
Definition at line 1403 of file GaitGenerator.h.
void rats::gait_generator::set_act_contact_states | ( | const std::vector< bool > & | _act_contact_states | ) | [inline] |
Definition at line 1299 of file GaitGenerator.h.
void rats::gait_generator::set_all_limbs | ( | const std::vector< std::string > & | _all_limbs | ) | [inline] |
Definition at line 1262 of file GaitGenerator.h.
void rats::gait_generator::set_cp_check_margin | ( | const double(&) | _cp_check_margin[2] | ) | [inline] |
Definition at line 1294 of file GaitGenerator.h.
void rats::gait_generator::set_cycloid_delay_kick_point_offset | ( | const hrp::Vector3 | _offset | ) | [inline] |
Definition at line 1247 of file GaitGenerator.h.
void rats::gait_generator::set_default_double_support_ratio_after | ( | const double | _default_double_support_ratio_after | ) | [inline] |
Definition at line 1210 of file GaitGenerator.h.
void rats::gait_generator::set_default_double_support_ratio_before | ( | const double | _default_double_support_ratio_before | ) | [inline] |
Definition at line 1209 of file GaitGenerator.h.
void rats::gait_generator::set_default_double_support_ratio_swing_after | ( | const double | _default_double_support_ratio_swing_after | ) | [inline] |
Definition at line 1214 of file GaitGenerator.h.
void rats::gait_generator::set_default_double_support_ratio_swing_before | ( | const double | _default_double_support_ratio_swing_before | ) | [inline] |
Definition at line 1213 of file GaitGenerator.h.
void rats::gait_generator::set_default_double_support_static_ratio_after | ( | const double | _default_double_support_static_ratio_after | ) | [inline] |
Definition at line 1212 of file GaitGenerator.h.
void rats::gait_generator::set_default_double_support_static_ratio_before | ( | const double | _default_double_support_static_ratio_before | ) | [inline] |
Definition at line 1211 of file GaitGenerator.h.
void rats::gait_generator::set_default_orbit_type | ( | const orbit_type | type | ) | [inline] |
Definition at line 1242 of file GaitGenerator.h.
void rats::gait_generator::set_default_step_height | ( | const double | _tmp | ) | [inline] |
Definition at line 1221 of file GaitGenerator.h.
void rats::gait_generator::set_default_step_time | ( | const double | _default_step_time | ) | [inline] |
Definition at line 1208 of file GaitGenerator.h.
void rats::gait_generator::set_default_top_ratio | ( | const double | _tmp | ) | [inline] |
Definition at line 1222 of file GaitGenerator.h.
void rats::gait_generator::set_default_zmp_offsets | ( | const std::vector< hrp::Vector3 > & | tmp | ) | [inline] |
Definition at line 1215 of file GaitGenerator.h.
void rats::gait_generator::set_diff_cp | ( | const hrp::Vector3 | _cp | ) | [inline] |
Definition at line 1308 of file GaitGenerator.h.
void rats::gait_generator::set_foot_steps_list | ( | const std::vector< std::vector< step_node > > & | fnsl | ) | [inline] |
Definition at line 1264 of file GaitGenerator.h.
void rats::gait_generator::set_footstep_modification_gain | ( | const double | _footstep_modification_gain | ) | [inline] |
Definition at line 1293 of file GaitGenerator.h.
void rats::gait_generator::set_gravitational_acceleration | ( | const double | ga | ) | [inline] |
Definition at line 1248 of file GaitGenerator.h.
void rats::gait_generator::set_heel_angle | ( | const double | _angle | ) | [inline] |
Definition at line 1252 of file GaitGenerator.h.
void rats::gait_generator::set_heel_check_thre | ( | const double | _a | ) | [inline] |
Definition at line 1311 of file GaitGenerator.h.
void rats::gait_generator::set_heel_pos_offset_x | ( | const double | _offx | ) | [inline] |
Definition at line 1250 of file GaitGenerator.h.
void rats::gait_generator::set_heel_zmp_offset_x | ( | const double | _off | ) | [inline] |
Definition at line 1217 of file GaitGenerator.h.
void rats::gait_generator::set_leg_default_translate_pos | ( | const std::vector< hrp::Vector3 > & | off | ) | [inline] |
Definition at line 1260 of file GaitGenerator.h.
void rats::gait_generator::set_leg_margin | ( | const double | _leg_margin[4] | ) | [inline] |
Definition at line 1278 of file GaitGenerator.h.
void rats::gait_generator::set_margin_time_ratio | ( | const double | _margin_time_ratio | ) | [inline] |
Definition at line 1307 of file GaitGenerator.h.
void rats::gait_generator::set_modify_footsteps | ( | const bool | _modify_footsteps | ) | [inline] |
Definition at line 1306 of file GaitGenerator.h.
void rats::gait_generator::set_offset_velocity_param | ( | const double | vel_x, |
const double | vel_y, | ||
const double | vel_theta | ||
) | [inline] |
Definition at line 1227 of file GaitGenerator.h.
void rats::gait_generator::set_optional_go_pos_finalize_footstep_num | ( | const size_t | num | ) | [inline] |
Definition at line 1261 of file GaitGenerator.h.
void rats::gait_generator::set_overwritable_footstep_index_offset | ( | const size_t | _of | ) | [inline] |
Definition at line 1263 of file GaitGenerator.h.
void rats::gait_generator::set_overwritable_stride_limitation | ( | const double(&) | _overwritable_stride_limitation[5] | ) | [inline] |
Definition at line 1288 of file GaitGenerator.h.
bool rats::gait_generator::set_overwrite_foot_step_index | ( | const size_t | idx | ) | [inline] |
Definition at line 1317 of file GaitGenerator.h.
void rats::gait_generator::set_overwrite_foot_steps_list | ( | const std::vector< std::vector< step_node > > & | fnsl | ) | [inline] |
Definition at line 1271 of file GaitGenerator.h.
void rats::gait_generator::set_stair_trajectory_way_point_offset | ( | const hrp::Vector3 | _offset | ) | [inline] |
Definition at line 1246 of file GaitGenerator.h.
void rats::gait_generator::set_stride_limitation_for_circle_type | ( | const double(&) | _stride_limitation_for_circle_type[5] | ) | [inline] |
Definition at line 1283 of file GaitGenerator.h.
void rats::gait_generator::set_stride_limitation_type | ( | const stride_limitation_type | _tmp | ) | [inline] |
Definition at line 1309 of file GaitGenerator.h.
void rats::gait_generator::set_stride_parameters | ( | const double | _stride_fwd_x, |
const double | _stride_outside_y, | ||
const double | _stride_outside_theta, | ||
const double | _stride_bwd_x, | ||
const double | _stride_inside_y, | ||
const double | _stride_inside_theta | ||
) | [inline] |
Definition at line 1231 of file GaitGenerator.h.
void rats::gait_generator::set_swing_trajectory_delay_time_offset | ( | const double | _time_offset | ) | [inline] |
Definition at line 1243 of file GaitGenerator.h.
void rats::gait_generator::set_swing_trajectory_final_distance_weight | ( | const double | _final_distance_weight | ) | [inline] |
Definition at line 1244 of file GaitGenerator.h.
void rats::gait_generator::set_swing_trajectory_time_offset_xy2z | ( | const double | _tmp | ) | [inline] |
Definition at line 1245 of file GaitGenerator.h.
void rats::gait_generator::set_toe_angle | ( | const double | _angle | ) | [inline] |
Definition at line 1251 of file GaitGenerator.h.
void rats::gait_generator::set_toe_check_thre | ( | const double | _a | ) | [inline] |
Definition at line 1310 of file GaitGenerator.h.
bool rats::gait_generator::set_toe_heel_phase_ratio | ( | const std::vector< double > & | ratio | ) | [inline] |
Definition at line 1253 of file GaitGenerator.h.
void rats::gait_generator::set_toe_pos_offset_x | ( | const double | _offx | ) | [inline] |
Definition at line 1249 of file GaitGenerator.h.
void rats::gait_generator::set_toe_zmp_offset_x | ( | const double | _off | ) | [inline] |
Definition at line 1216 of file GaitGenerator.h.
void rats::gait_generator::set_use_inside_step_limitation | ( | const bool | uu | ) | [inline] |
Definition at line 1241 of file GaitGenerator.h.
void rats::gait_generator::set_use_stride_limitation | ( | const bool | _use_stride_limitation | ) | [inline] |
Definition at line 1305 of file GaitGenerator.h.
void rats::gait_generator::set_use_toe_heel_auto_set | ( | const bool | _u | ) | [inline] |
Definition at line 1219 of file GaitGenerator.h.
void rats::gait_generator::set_use_toe_heel_transition | ( | const bool | _u | ) | [inline] |
Definition at line 1218 of file GaitGenerator.h.
void rats::gait_generator::set_use_toe_joint | ( | const bool | ut | ) | [inline] |
Definition at line 1259 of file GaitGenerator.h.
void rats::gait_generator::set_velocity_param | ( | const double | vel_x, |
const double | vel_y, | ||
const double | vel_theta | ||
) | [inline] |
Definition at line 1223 of file GaitGenerator.h.
void rats::gait_generator::set_zmp_weight_map | ( | const std::map< leg_type, double > | _map | ) | [inline] |
Definition at line 1220 of file GaitGenerator.h.
std::vector<bool> rats::gait_generator::act_contact_states [private] |
Definition at line 1062 of file GaitGenerator.h.
std::vector<std::string> rats::gait_generator::all_limbs [private] |
Definition at line 1040 of file GaitGenerator.h.
hrp::Vector3 rats::gait_generator::cog [private] |
Definition at line 1037 of file GaitGenerator.h.
double rats::gait_generator::cp_check_margin[2] [private] |
Definition at line 1059 of file GaitGenerator.h.
double rats::gait_generator::default_double_support_ratio_after [private] |
Definition at line 1042 of file GaitGenerator.h.
double rats::gait_generator::default_double_support_ratio_before [private] |
Definition at line 1042 of file GaitGenerator.h.
double rats::gait_generator::default_double_support_ratio_swing_after [private] |
Definition at line 1044 of file GaitGenerator.h.
double rats::gait_generator::default_double_support_ratio_swing_before [private] |
Definition at line 1043 of file GaitGenerator.h.
double rats::gait_generator::default_double_support_static_ratio_after [private] |
Definition at line 1042 of file GaitGenerator.h.
double rats::gait_generator::default_double_support_static_ratio_before [private] |
Definition at line 1042 of file GaitGenerator.h.
double rats::gait_generator::default_step_time [private] |
Definition at line 1041 of file GaitGenerator.h.
Definition at line 1063 of file GaitGenerator.h.
hrp::Vector3 rats::gait_generator::diff_cp [private] |
Definition at line 1061 of file GaitGenerator.h.
double rats::gait_generator::dt [private] |
Definition at line 1039 of file GaitGenerator.h.
Definition at line 1054 of file GaitGenerator.h.
size_t rats::gait_generator::finalize_count [private] |
Definition at line 1046 of file GaitGenerator.h.
double rats::gait_generator::footstep_modification_gain [private] |
Definition at line 1059 of file GaitGenerator.h.
std::vector< std::vector<step_node> > rats::gait_generator::footstep_nodes_list [private] |
Definition at line 1029 of file GaitGenerator.h.
Definition at line 1034 of file GaitGenerator.h.
double rats::gait_generator::gravitational_acceleration [private] |
Definition at line 1045 of file GaitGenerator.h.
Definition at line 1057 of file GaitGenerator.h.
bool rats::gait_generator::is_emergency_walking[2] [private] |
Definition at line 1060 of file GaitGenerator.h.
Definition at line 1033 of file GaitGenerator.h.
double rats::gait_generator::leg_margin[4] [private] |
Definition at line 1059 of file GaitGenerator.h.
std::map<leg_type, std::string> rats::gait_generator::leg_type_map [private] |
Definition at line 1056 of file GaitGenerator.h.
double rats::gait_generator::margin_time_ratio [private] |
Definition at line 1059 of file GaitGenerator.h.
Definition at line 1061 of file GaitGenerator.h.
bool rats::gait_generator::modify_footsteps [private] |
Definition at line 1060 of file GaitGenerator.h.
Definition at line 1035 of file GaitGenerator.h.
size_t rats::gait_generator::optional_go_pos_finalize_footstep_num [private] |
Definition at line 1046 of file GaitGenerator.h.
size_t rats::gait_generator::overwritable_footstep_index_offset [private] |
Definition at line 1052 of file GaitGenerator.h.
double rats::gait_generator::overwritable_stride_limitation[5] [private] |
Definition at line 1059 of file GaitGenerator.h.
size_t rats::gait_generator::overwrite_footstep_index [private] |
Definition at line 1049 of file GaitGenerator.h.
std::vector< std::vector<step_node> > rats::gait_generator::overwrite_footstep_nodes_list [private] |
Definition at line 1031 of file GaitGenerator.h.
Definition at line 1037 of file GaitGenerator.h.
std::vector<hrp::Vector3> rats::gait_generator::prev_que_sfzos [private] |
Definition at line 1038 of file GaitGenerator.h.
preview_dynamics_filter<extended_preview_control>* rats::gait_generator::preview_controller_ptr [private] |
Definition at line 1067 of file GaitGenerator.h.
hrp::Vector3 rats::gait_generator::refzmp [private] |
Definition at line 1037 of file GaitGenerator.h.
refzmp_generator rats::gait_generator::rg [private] |
Definition at line 1032 of file GaitGenerator.h.
bool rats::gait_generator::solved [private] |
Definition at line 1058 of file GaitGenerator.h.
double rats::gait_generator::stride_limitation_for_circle_type[5] [private] |
Definition at line 1059 of file GaitGenerator.h.
std::vector<hrp::Vector3> rats::gait_generator::swing_foot_zmp_offsets [private] |
Definition at line 1038 of file GaitGenerator.h.
Definition at line 1036 of file GaitGenerator.h.
bool rats::gait_generator::use_inside_step_limitation [private] |
Definition at line 1055 of file GaitGenerator.h.
bool rats::gait_generator::use_stride_limitation [private] |
Definition at line 1060 of file GaitGenerator.h.
Definition at line 1035 of file GaitGenerator.h.
Definition at line 1053 of file GaitGenerator.h.