Basic RT components and utilities  315.15.0
Public Attributes | List of all members
OpenHRP::AutoBalancerService::GaitGeneratorParam Struct Reference

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_ratio_before
 Ratio of first double support period. Ratio is included in (0, 1). First double support period time is default_double_support_ratio_before*default_step_time. More...
 
double default_double_support_ratio_after
 Ratio of last double support period. Ratio is included in (0, 1). Last double support period time is default_double_support_ratio_after*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...
 
double default_double_support_static_ratio_before
 Ratio of first double support static period in which reference ZMP does not move. Ratio is included in (0, 1). default_double_support_ratio_before >= default_double_support_static_ratio_before.. More...
 
double default_double_support_static_ratio_after
 Ratio of last double support static period in which reference ZMP does not move. Ratio is included in (0, 1). default_double_support_ratio_after >= default_double_support_static_ratio_after.. More...
 
double default_double_support_ratio_swing_before
 Ratio of double support period before swing. Ratio is included in (0, 1). More...
 
double default_double_support_ratio_swing_after
 Ratio of double support period after swing. Ratio is included in (0, 1). More...
 
sequence< double, 6 > stride_parameter
 Stride limitation of forward x[m], outside y[m], outside theta[deg], backward x[m], inside y[m], inside theta[deg] for goPos and goVelocity. More...
 
DblArray5 stride_limitation_for_circle_type
 Stride limitation when generating footsteps with stride limitation type CIRCLE (forward, outside, theta, backward, inside) [m]. 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 swing_trajectory_time_offset_xy2z
 Time offset between Z convergence to antecedent path and XY convergence. [swing time]=[Z convergence time]=[XY convergence time]-[swing_trajectory_xy_time_offset]. 0 by default, this means Z convergence time and XY convergence time are same. 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...
 
double toe_check_thre
 Threshould [m] (>=0) whether toe is used or not. This is used only if use_toe_heel_auto_set == true. More...
 
double heel_check_thre
 Threshould [m] (>=0) whether heel is used or not. This is used only if use_toe_heel_auto_set == true. 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...
 
boolean use_toe_heel_auto_set
 Use toe heel auto setting. If true, gait generator autonomously determine whether toe and heel are used. More...
 
sequence< double, 4 > zmp_weight_map
 ZMP weight of RLEG, LLEG, RARM and LARM. More...
 
sequence< DblSequence3leg_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...
 
long overwritable_footstep_index_offset
 Offset for overwritable footstep index. Offset from current footstep index. Used in emergency_stop and velocity_mode. More...
 
DblArray5 overwritable_stride_limitation
 Stride limitation when overwriting footsteps (forward, outside, theta, backward, inside) [m]. More...
 
boolean use_stride_limitation
 Use stride limitation or not. More...
 
StrideLimitationType stride_limitation_type
 Stride limitation type. More...
 
DblArray4 leg_margin
 Leg margin between foot end effector position and foot edge (front, rear, outside, inside) [m]. More...
 
double footstep_modification_gain
 Feedback gain when modifying footsteps based on Capture Point. More...
 
boolean modify_footsteps
 Whether modify footsteps based on Capture Point. More...
 
DblArray2 cp_check_margin
 CP check margin when modifying footsteps (x, y) [m]. More...
 
double margin_time_ratio
 Margin time ratio for footstep modification before landing [s]. More...
 

Detailed Description

Parameters for GaitGenerator.

Member Data Documentation

◆ cp_check_margin

DblArray2 OpenHRP::AutoBalancerService::GaitGeneratorParam::cp_check_margin

CP check margin when modifying footsteps (x, y) [m].

◆ cycloid_delay_kick_point_offset

DblArray3 OpenHRP::AutoBalancerService::GaitGeneratorParam::cycloid_delay_kick_point_offset

Kick point offset 3D vector [m] for cycloid_delay_kick_hoffarbib_trajectory_generator.

◆ default_double_support_ratio

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.

◆ default_double_support_ratio_after

double OpenHRP::AutoBalancerService::GaitGeneratorParam::default_double_support_ratio_after

Ratio of last double support period. Ratio is included in (0, 1). Last double support period time is default_double_support_ratio_after*default_step_time.

◆ default_double_support_ratio_before

double OpenHRP::AutoBalancerService::GaitGeneratorParam::default_double_support_ratio_before

Ratio of first double support period. Ratio is included in (0, 1). First double support period time is default_double_support_ratio_before*default_step_time.

◆ default_double_support_ratio_swing_after

double OpenHRP::AutoBalancerService::GaitGeneratorParam::default_double_support_ratio_swing_after

Ratio of double support period after swing. Ratio is included in (0, 1).

◆ default_double_support_ratio_swing_before

double OpenHRP::AutoBalancerService::GaitGeneratorParam::default_double_support_ratio_swing_before

Ratio of double support period before swing. Ratio is included in (0, 1).

◆ default_double_support_static_ratio

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..

◆ default_double_support_static_ratio_after

double OpenHRP::AutoBalancerService::GaitGeneratorParam::default_double_support_static_ratio_after

Ratio of last double support static period in which reference ZMP does not move. Ratio is included in (0, 1). default_double_support_ratio_after >= default_double_support_static_ratio_after..

◆ default_double_support_static_ratio_before

double OpenHRP::AutoBalancerService::GaitGeneratorParam::default_double_support_static_ratio_before

Ratio of first double support static period in which reference ZMP does not move. Ratio is included in (0, 1). default_double_support_ratio_before >= default_double_support_static_ratio_before..

◆ default_orbit_type

OrbitType OpenHRP::AutoBalancerService::GaitGeneratorParam::default_orbit_type

Default OrbitType.

◆ default_step_height

double OpenHRP::AutoBalancerService::GaitGeneratorParam::default_step_height

Step height [m].

◆ default_step_time

double OpenHRP::AutoBalancerService::GaitGeneratorParam::default_step_time

Step time [s].

◆ footstep_modification_gain

double OpenHRP::AutoBalancerService::GaitGeneratorParam::footstep_modification_gain

Feedback gain when modifying footsteps based on Capture Point.

◆ gravitational_acceleration

double OpenHRP::AutoBalancerService::GaitGeneratorParam::gravitational_acceleration

Gravitational acceleration [m/s^2].

◆ heel_angle

double OpenHRP::AutoBalancerService::GaitGeneratorParam::heel_angle

Maximum heel angle [deg] for heel-contact motion.

◆ heel_check_thre

double OpenHRP::AutoBalancerService::GaitGeneratorParam::heel_check_thre

Threshould [m] (>=0) whether heel is used or not. This is used only if use_toe_heel_auto_set == true.

◆ heel_pos_offset_x

double OpenHRP::AutoBalancerService::GaitGeneratorParam::heel_pos_offset_x

Heel position offset [m] in end-effector frame x axis.

◆ heel_zmp_offset_x

double OpenHRP::AutoBalancerService::GaitGeneratorParam::heel_zmp_offset_x

Heel ZMP offset [m] in end-effector frame x axis.

◆ leg_default_translate_pos

sequence<DblSequence3> OpenHRP::AutoBalancerService::GaitGeneratorParam::leg_default_translate_pos

Foot position offset[m] (rleg and lleg)

◆ leg_margin

DblArray4 OpenHRP::AutoBalancerService::GaitGeneratorParam::leg_margin

Leg margin between foot end effector position and foot edge (front, rear, outside, inside) [m].

◆ margin_time_ratio

double OpenHRP::AutoBalancerService::GaitGeneratorParam::margin_time_ratio

Margin time ratio for footstep modification before landing [s].

◆ modify_footsteps

boolean OpenHRP::AutoBalancerService::GaitGeneratorParam::modify_footsteps

Whether modify footsteps based on Capture Point.

◆ optional_go_pos_finalize_footstep_num

long OpenHRP::AutoBalancerService::GaitGeneratorParam::optional_go_pos_finalize_footstep_num

Number of optional finalize footsteps in goPos.

◆ overwritable_footstep_index_offset

long OpenHRP::AutoBalancerService::GaitGeneratorParam::overwritable_footstep_index_offset

Offset for overwritable footstep index. Offset from current footstep index. Used in emergency_stop and velocity_mode.

◆ overwritable_stride_limitation

DblArray5 OpenHRP::AutoBalancerService::GaitGeneratorParam::overwritable_stride_limitation

Stride limitation when overwriting footsteps (forward, outside, theta, backward, inside) [m].

◆ stair_trajectory_way_point_offset

DblArray3 OpenHRP::AutoBalancerService::GaitGeneratorParam::stair_trajectory_way_point_offset

Way point offset 3D vector [m] for stair_delay_hoffarbib_trajectory_generator.

◆ stride_limitation_for_circle_type

DblArray5 OpenHRP::AutoBalancerService::GaitGeneratorParam::stride_limitation_for_circle_type

Stride limitation when generating footsteps with stride limitation type CIRCLE (forward, outside, theta, backward, inside) [m].

◆ stride_limitation_type

StrideLimitationType OpenHRP::AutoBalancerService::GaitGeneratorParam::stride_limitation_type

Stride limitation type.

◆ stride_parameter

sequence<double, 6> OpenHRP::AutoBalancerService::GaitGeneratorParam::stride_parameter

Stride limitation of forward x[m], outside y[m], outside theta[deg], backward x[m], inside y[m], inside theta[deg] for goPos and goVelocity.

◆ swing_trajectory_delay_time_offset

double OpenHRP::AutoBalancerService::GaitGeneratorParam::swing_trajectory_delay_time_offset

Time offset [s] for swing trajectory by delay_hoffarbib_trajectory_generator.

◆ swing_trajectory_final_distance_weight

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).

◆ swing_trajectory_time_offset_xy2z

double OpenHRP::AutoBalancerService::GaitGeneratorParam::swing_trajectory_time_offset_xy2z

Time offset between Z convergence to antecedent path and XY convergence. [swing time]=[Z convergence time]=[XY convergence time]-[swing_trajectory_xy_time_offset]. 0 by default, this means Z convergence time and XY convergence time are same.

◆ toe_angle

double OpenHRP::AutoBalancerService::GaitGeneratorParam::toe_angle

Maximum toe angle [deg] for toe-off motion.

◆ toe_check_thre

double OpenHRP::AutoBalancerService::GaitGeneratorParam::toe_check_thre

Threshould [m] (>=0) whether toe is used or not. This is used only if use_toe_heel_auto_set == true.

◆ toe_heel_phase_ratio

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.

◆ toe_pos_offset_x

double OpenHRP::AutoBalancerService::GaitGeneratorParam::toe_pos_offset_x

Toe position offset [m] in end-effector frame x axis.

◆ toe_zmp_offset_x

double OpenHRP::AutoBalancerService::GaitGeneratorParam::toe_zmp_offset_x

Toe ZMP offset [m] in end-effector frame x axis.

◆ use_stride_limitation

boolean OpenHRP::AutoBalancerService::GaitGeneratorParam::use_stride_limitation

Use stride limitation or not.

◆ use_toe_heel_auto_set

boolean OpenHRP::AutoBalancerService::GaitGeneratorParam::use_toe_heel_auto_set

Use toe heel auto setting. If true, gait generator autonomously determine whether toe and heel are used.

◆ use_toe_heel_transition

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).

◆ use_toe_joint

boolean OpenHRP::AutoBalancerService::GaitGeneratorParam::use_toe_joint

Use toe joint or not in toe-off heel-contact motion.

◆ zmp_weight_map

sequence<double, 4> OpenHRP::AutoBalancerService::GaitGeneratorParam::zmp_weight_map

ZMP weight of RLEG, LLEG, RARM and LARM.


The documentation for this struct was generated from the following file: