Basic RT components and utilities
315.7.0
|
Parameters for GaitGenerator. More...
import "AutoBalancerService.idl";
Public Attributes | |
double | default_step_time |
Step time [s]. More... | |
double | default_step_height |
Step height [m]. More... | |
double | default_double_support_ratio |
Ratio of double support period. Ratio is included in (0, 1). Double support period time is default_double_support_ratio*default_step_time. More... | |
double | default_double_support_static_ratio |
Ratio of double support static period in which reference ZMP does not move. Ratio is included in (0, 1). default_double_support_ratio >= default_double_support_static_ratio.. More... | |
sequence< double, 4 > | stride_parameter |
Stride limitation of forward x[m], y[m], theta[deg], and backward x[m] for goPos. More... | |
OrbitType | default_orbit_type |
Default OrbitType. More... | |
double | swing_trajectory_delay_time_offset |
Time offset [s] for swing trajectory by delay_hoffarbib_trajectory_generator. More... | |
double | swing_trajectory_final_distance_weight |
Weight parameter for distance of final path of delay_hoffarbib_trajectory_generator (1.0 by default). More... | |
DblArray3 | stair_trajectory_way_point_offset |
Way point offset 3D vector [m] for stair_delay_hoffarbib_trajectory_generator. More... | |
DblArray3 | cycloid_delay_kick_point_offset |
Kick point offset 3D vector [m] for cycloid_delay_kick_hoffarbib_trajectory_generator. More... | |
double | gravitational_acceleration |
Gravitational acceleration [m/s^2]. More... | |
double | toe_pos_offset_x |
Toe position offset [m] in end-effector frame x axis. More... | |
double | heel_pos_offset_x |
Heel position offset [m] in end-effector frame x axis. More... | |
double | toe_zmp_offset_x |
Toe ZMP offset [m] in end-effector frame x axis. More... | |
double | heel_zmp_offset_x |
Heel ZMP offset [m] in end-effector frame x axis. More... | |
double | toe_angle |
Maximum toe angle [deg] for toe-off motion. More... | |
double | heel_angle |
Maximum heel angle [deg] for heel-contact motion. More... | |
sequence< double > | toe_heel_phase_ratio |
Sequence of phase ratio of toe-off and heel-contact. Sum of toe_heel_phase_ratio should be 1.0. More... | |
boolean | use_toe_joint |
Use toe joint or not in toe-off heel-contact motion. More... | |
boolean | use_toe_heel_transition |
Use toe heel zmp transition. If true, zmp moves among default position, toe position (described by toe_zmp_offset_x), and heel position (described by heel_zmp_offset_x). More... | |
sequence< DblSequence3 > | leg_default_translate_pos |
Foot position offset[m] (rleg and lleg) More... | |
long | optional_go_pos_finalize_footstep_num |
Number of optional finalize footsteps in goPos. More... | |
Parameters for GaitGenerator.
DblArray3 OpenHRP::AutoBalancerService::GaitGeneratorParam::cycloid_delay_kick_point_offset |
Kick point offset 3D vector [m] for cycloid_delay_kick_hoffarbib_trajectory_generator.
double OpenHRP::AutoBalancerService::GaitGeneratorParam::default_double_support_ratio |
Ratio of double support period. Ratio is included in (0, 1). Double support period time is default_double_support_ratio*default_step_time.
double OpenHRP::AutoBalancerService::GaitGeneratorParam::default_double_support_static_ratio |
Ratio of double support static period in which reference ZMP does not move. Ratio is included in (0, 1). default_double_support_ratio >= default_double_support_static_ratio..
OrbitType OpenHRP::AutoBalancerService::GaitGeneratorParam::default_orbit_type |
Default OrbitType.
double OpenHRP::AutoBalancerService::GaitGeneratorParam::default_step_height |
Step height [m].
double OpenHRP::AutoBalancerService::GaitGeneratorParam::default_step_time |
Step time [s].
double OpenHRP::AutoBalancerService::GaitGeneratorParam::gravitational_acceleration |
Gravitational acceleration [m/s^2].
double OpenHRP::AutoBalancerService::GaitGeneratorParam::heel_angle |
Maximum heel angle [deg] for heel-contact motion.
double OpenHRP::AutoBalancerService::GaitGeneratorParam::heel_pos_offset_x |
Heel position offset [m] in end-effector frame x axis.
double OpenHRP::AutoBalancerService::GaitGeneratorParam::heel_zmp_offset_x |
Heel ZMP offset [m] in end-effector frame x axis.
sequence<DblSequence3> OpenHRP::AutoBalancerService::GaitGeneratorParam::leg_default_translate_pos |
Foot position offset[m] (rleg and lleg)
long OpenHRP::AutoBalancerService::GaitGeneratorParam::optional_go_pos_finalize_footstep_num |
Number of optional finalize footsteps in goPos.
DblArray3 OpenHRP::AutoBalancerService::GaitGeneratorParam::stair_trajectory_way_point_offset |
Way point offset 3D vector [m] for stair_delay_hoffarbib_trajectory_generator.
sequence<double, 4> OpenHRP::AutoBalancerService::GaitGeneratorParam::stride_parameter |
Stride limitation of forward x[m], y[m], theta[deg], and backward x[m] for goPos.
double OpenHRP::AutoBalancerService::GaitGeneratorParam::swing_trajectory_delay_time_offset |
Time offset [s] for swing trajectory by delay_hoffarbib_trajectory_generator.
double OpenHRP::AutoBalancerService::GaitGeneratorParam::swing_trajectory_final_distance_weight |
Weight parameter for distance of final path of delay_hoffarbib_trajectory_generator (1.0 by default).
double OpenHRP::AutoBalancerService::GaitGeneratorParam::toe_angle |
Maximum toe angle [deg] for toe-off motion.
sequence<double> OpenHRP::AutoBalancerService::GaitGeneratorParam::toe_heel_phase_ratio |
Sequence of phase ratio of toe-off and heel-contact. Sum of toe_heel_phase_ratio should be 1.0.
double OpenHRP::AutoBalancerService::GaitGeneratorParam::toe_pos_offset_x |
Toe position offset [m] in end-effector frame x axis.
double OpenHRP::AutoBalancerService::GaitGeneratorParam::toe_zmp_offset_x |
Toe ZMP offset [m] in end-effector frame x axis.
boolean OpenHRP::AutoBalancerService::GaitGeneratorParam::use_toe_heel_transition |
Use toe heel zmp transition. If true, zmp moves among default position, toe position (described by toe_zmp_offset_x), and heel position (described by heel_zmp_offset_x).
boolean OpenHRP::AutoBalancerService::GaitGeneratorParam::use_toe_joint |
Use toe joint or not in toe-off heel-contact motion.