|
void | append_finalize_footstep () |
|
void | append_finalize_footstep (std::vector< std::vector< step_node > > &_footstep_nodes_list) const |
|
void | append_footstep_nodes (const std::vector< std::string > &_legs, const std::vector< coordinates > &_fss) |
|
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) |
|
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 |
|
void | clear_footstep_nodes_list () |
|
std::vector< std::string > | convert_leg_types_to_names (const std::vector< leg_type > <s) const |
|
void | emergency_stop () |
|
void | finalize_velocity_mode () |
|
| 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) |
|
hrp::Vector3 | get_cart_zmp () const |
|
const hrp::Vector3 & | get_cog () const |
|
hrp::Vector3 | get_cog_acc () const |
|
hrp::Vector3 | get_cog_vel () const |
|
double | get_cp_check_margin (const size_t idx) const |
|
bool | get_current_support_state_from_ee_name (const std::string &ee_name) const |
|
std::vector< leg_type > | get_current_support_states () const |
|
double | get_current_swing_time (const size_t idx) const |
|
double | get_current_swing_time_from_ee_name (const std::string ee_name) const |
|
double | get_current_toe_heel_ratio () const |
|
bool | get_current_toe_heel_ratio_from_ee_name (double &ret, const std::string &ee_name) const |
|
hrp::Vector3 | get_cycloid_delay_kick_point_offset () const |
|
double | get_default_double_support_ratio_after () const |
|
double | get_default_double_support_ratio_before () const |
|
double | get_default_double_support_ratio_swing_after () const |
|
double | get_default_double_support_ratio_swing_before () const |
|
double | get_default_double_support_static_ratio_after () const |
|
double | get_default_double_support_static_ratio_before () const |
|
orbit_type | get_default_orbit_type () const |
|
double | get_default_step_height () const |
|
double | get_default_step_time () const |
|
const coordinates | get_dst_foot_midcoords () const |
|
double | get_foot_dif_rot_angle () const |
|
std::vector< std::string > | get_footstep_back_leg_names () const |
|
std::vector< std::string > | get_footstep_front_leg_names () const |
|
size_t | get_footstep_index () const |
|
double | get_footstep_modification_gain () const |
|
bool | get_footstep_nodes_by_index (std::vector< step_node > &csl, const size_t idx) const |
|
double | get_gravitational_acceleration () const |
|
double | get_heel_angle () const |
|
double | get_heel_check_thre () const |
|
double | get_heel_pos_offset_x () const |
|
double | get_heel_zmp_offset_x () const |
|
size_t | get_lcg_count () const |
|
void | get_leg_default_translate_pos (std::vector< hrp::Vector3 > &off) const |
|
double | get_leg_margin (const size_t idx) const |
|
const std::map< leg_type, std::string > | get_leg_type_map () const |
|
double | get_margin_time_ratio () const |
|
bool | get_modify_footsteps () const |
|
int | get_NUM_TH_PHASES () const |
|
size_t | get_optional_go_pos_finalize_footstep_num () const |
|
size_t | get_overwritable_footstep_index_offset () const |
|
size_t | get_overwritable_index () const |
|
double | get_overwritable_stride_limitation (const size_t idx) const |
|
size_t | get_overwrite_check_timing () const |
|
const hrp::Vector3 & | get_refzmp () const |
|
std::vector< std::vector< step_node > > | get_remaining_footstep_nodes_list () const |
|
hrp::Vector3 | get_stair_trajectory_way_point_offset () const |
|
double | get_stride_limitation_for_circle_type (const size_t idx) const |
|
stride_limitation_type | get_stride_limitation_type () const |
|
void | 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 |
|
std::vector< hrp::Vector3 > | get_support_foot_zmp_offsets () const |
|
const std::vector< std::string > | get_support_leg_names () const |
|
const std::vector< step_node > & | get_support_leg_steps () const |
|
const std::vector< hrp::Vector3 > & | get_swing_foot_zmp_offsets () const |
|
const std::vector< step_node > & | get_swing_leg_dst_steps () const |
|
const std::vector< std::string > | get_swing_leg_names () const |
|
const std::vector< step_node > & | get_swing_leg_src_steps () const |
|
const std::vector< step_node > & | get_swing_leg_steps () const |
|
bool | get_swing_support_ee_coords_from_ee_name (hrp::Vector3 &cpos, hrp::Matrix33 &crot, const std::string &ee_name) const |
|
bool | get_swing_support_foot_zmp_offsets_from_ee_name (hrp::Vector3 &ret, const std::string &ee_name) const |
|
void | get_swing_support_mid_coords (coordinates &ret) const |
|
double | get_swing_trajectory_delay_time_offset () const |
|
double | get_swing_trajectory_final_distance_weight () const |
|
double | get_swing_trajectory_time_offset_xy2z () const |
|
double | get_toe_angle () const |
|
double | get_toe_check_thre () const |
|
void | get_toe_heel_phase_ratio (std::vector< double > &ratio) const |
|
double | get_toe_pos_offset_x () const |
|
double | get_toe_zmp_offset_x () const |
|
bool | get_use_stride_limitation () const |
|
bool | get_use_toe_heel_auto_set () const |
|
bool | get_use_toe_heel_transition () const |
|
bool | get_use_toe_joint () const |
|
const std::map< leg_type, double > | get_zmp_weight_map () const |
|
bool | 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) |
|
bool | 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) |
|
void | 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 |
|
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, const std::string &tmp_swing_leg, const coordinates &_support_leg_coords) |
|
void | 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) |
|
void | initialize_velocity_mode (const coordinates &_ref_coords, const double vel_x, const double vel_y, const double vel_theta, const std::vector< leg_type > ¤t_legs) |
|
bool | is_finalizing (const double tm) const |
|
void | limit_stride (step_node &cur_fs, const step_node &prev_fs, const double(&limit)[5]) const |
|
void | modify_footsteps_for_recovery () |
|
void | print_footstep_nodes_list (const std::vector< std::vector< step_node > > _footstep_nodes_list) const |
|
void | print_footstep_nodes_list () const |
|
void | print_param (const std::string &print_str="") const |
|
bool | proc_one_tick () |
|
void | proc_zmp_weight_map_interpolation () |
|
void | set_act_contact_states (const std::vector< bool > &_act_contact_states) |
|
void | set_all_limbs (const std::vector< std::string > &_all_limbs) |
|
void | set_cp_check_margin (const double(&_cp_check_margin)[2]) |
|
void | set_cycloid_delay_kick_point_offset (const hrp::Vector3 _offset) |
|
void | set_default_double_support_ratio_after (const double _default_double_support_ratio_after) |
|
void | set_default_double_support_ratio_before (const double _default_double_support_ratio_before) |
|
void | set_default_double_support_ratio_swing_after (const double _default_double_support_ratio_swing_after) |
|
void | set_default_double_support_ratio_swing_before (const double _default_double_support_ratio_swing_before) |
|
void | set_default_double_support_static_ratio_after (const double _default_double_support_static_ratio_after) |
|
void | set_default_double_support_static_ratio_before (const double _default_double_support_static_ratio_before) |
|
void | set_default_orbit_type (const orbit_type type) |
|
void | set_default_step_height (const double _tmp) |
|
void | set_default_step_time (const double _default_step_time) |
|
void | set_default_top_ratio (const double _tmp) |
|
void | set_default_zmp_offsets (const std::vector< hrp::Vector3 > &tmp) |
|
void | set_diff_cp (const hrp::Vector3 _cp) |
|
void | set_foot_steps_list (const std::vector< std::vector< step_node > > &fnsl) |
|
void | set_footstep_modification_gain (const double _footstep_modification_gain) |
|
void | set_gravitational_acceleration (const double ga) |
|
void | set_heel_angle (const double _angle) |
|
void | set_heel_check_thre (const double _a) |
|
void | set_heel_pos_offset_x (const double _offx) |
|
void | set_heel_zmp_offset_x (const double _off) |
|
void | set_leg_default_translate_pos (const std::vector< hrp::Vector3 > &off) |
|
void | set_leg_margin (const double _leg_margin[4]) |
|
void | set_margin_time_ratio (const double _margin_time_ratio) |
|
void | set_modify_footsteps (const bool _modify_footsteps) |
|
void | set_offset_velocity_param (const double vel_x, const double vel_y, const double vel_theta) |
|
void | set_optional_go_pos_finalize_footstep_num (const size_t num) |
|
void | set_overwritable_footstep_index_offset (const size_t _of) |
|
void | set_overwritable_stride_limitation (const double(&_overwritable_stride_limitation)[5]) |
|
bool | set_overwrite_foot_step_index (const size_t idx) |
|
void | set_overwrite_foot_steps_list (const std::vector< std::vector< step_node > > &fnsl) |
|
void | set_stair_trajectory_way_point_offset (const hrp::Vector3 _offset) |
|
void | set_stride_limitation_for_circle_type (const double(&_stride_limitation_for_circle_type)[5]) |
|
void | set_stride_limitation_type (const stride_limitation_type _tmp) |
|
void | 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) |
|
void | set_swing_trajectory_delay_time_offset (const double _time_offset) |
|
void | set_swing_trajectory_final_distance_weight (const double _final_distance_weight) |
|
void | set_swing_trajectory_time_offset_xy2z (const double _tmp) |
|
void | set_toe_angle (const double _angle) |
|
void | set_toe_check_thre (const double _a) |
|
bool | set_toe_heel_phase_ratio (const std::vector< double > &ratio) |
|
void | set_toe_pos_offset_x (const double _offx) |
|
void | set_toe_zmp_offset_x (const double _off) |
|
void | set_use_inside_step_limitation (const bool uu) |
|
void | set_use_stride_limitation (const bool _use_stride_limitation) |
|
void | set_use_toe_heel_auto_set (const bool _u) |
|
void | set_use_toe_heel_transition (const bool _u) |
|
void | set_use_toe_joint (const bool ut) |
|
void | set_velocity_param (const double vel_x, const double vel_y, const double vel_theta) |
|
void | set_zmp_weight_map (const std::map< leg_type, double > _map) |
|
| ~gait_generator () |
|