Basic RT components and utilities  315.12.1
Public Attributes
OpenHRP::AutoBalancerService::GaitGeneratorParam Struct Reference

Parameters for GaitGenerator. More...

import "AutoBalancerService.idl";

List of all members.

Public Attributes

double default_step_time
 Step time [s].
double default_step_height
 Step height [m].
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.
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.
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.
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..
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..
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..
double default_double_support_ratio_swing_before
 Ratio of double support period before swing. Ratio is included in (0, 1).
double default_double_support_ratio_swing_after
 Ratio of double support period after swing. Ratio is included in (0, 1).
sequence< double, 4 > stride_parameter
 Stride limitation of forward x[m], y[m], theta[deg], and backward x[m] for goPos.
DblArray5 stride_limitation_for_circle_type
 Stride limitation when generating footsteps with stride limitation type CIRCLE (forward, outside, theta, backward, inside) [m].
OrbitType default_orbit_type
 Default OrbitType.
double swing_trajectory_delay_time_offset
 Time offset [s] for swing trajectory by delay_hoffarbib_trajectory_generator.
double swing_trajectory_final_distance_weight
 Weight parameter for distance of final path of delay_hoffarbib_trajectory_generator (1.0 by default).
DblArray3 stair_trajectory_way_point_offset
 Way point offset 3D vector [m] for stair_delay_hoffarbib_trajectory_generator.
DblArray3 cycloid_delay_kick_point_offset
 Kick point offset 3D vector [m] for cycloid_delay_kick_hoffarbib_trajectory_generator.
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.
double gravitational_acceleration
 Gravitational acceleration [m/s^2].
double toe_pos_offset_x
 Toe position offset [m] in end-effector frame x axis.
double heel_pos_offset_x
 Heel position offset [m] in end-effector frame x axis.
double toe_zmp_offset_x
 Toe ZMP offset [m] in end-effector frame x axis.
double heel_zmp_offset_x
 Heel ZMP offset [m] in end-effector frame x axis.
double toe_angle
 Maximum toe angle [deg] for toe-off motion.
double heel_angle
 Maximum heel angle [deg] for heel-contact motion.
double toe_check_thre
 Threshould [m] (>=0) whether toe is used or not. This is used only if use_toe_heel_auto_set == true.
double heel_check_thre
 Threshould [m] (>=0) whether heel is used or not. This is used only if use_toe_heel_auto_set == true.
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.
boolean use_toe_joint
 Use toe joint or not in toe-off heel-contact motion.
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).
boolean use_toe_heel_auto_set
 Use toe heel auto setting. If true, gait generator autonomously determine whether toe and heel are used.
sequence< double, 4 > zmp_weight_map
 ZMP weight of RLEG, LLEG, RARM and LARM.
sequence< DblSequence3leg_default_translate_pos
 Foot position offset[m] (rleg and lleg)
long optional_go_pos_finalize_footstep_num
 Number of optional finalize footsteps in goPos.
long overwritable_footstep_index_offset
 Offset for overwritable footstep index. Offset from current footstep index. Used in emergency_stop and velocity_mode.
DblArray5 overwritable_stride_limitation
 Stride limitation when overwriting footsteps (forward, outside, theta, backward, inside) [m].
boolean use_stride_limitation
 Use stride limitation or not.
StrideLimitationType stride_limitation_type
 Stride limitation type.
DblArray4 leg_margin
 Leg margin between foot end effector position and foot edge (front, rear, outside, inside) [m].
double footstep_modification_gain
 Feedback gain when modifying footsteps based on Capture Point.
boolean modify_footsteps
 Whether modify footsteps based on Capture Point.
DblArray2 cp_check_margin
 CP check margin when modifying footsteps (x, y) [m].
double margin_time_ratio
 Margin time ratio for footstep modification before landing [s].

Detailed Description

Parameters for GaitGenerator.


Member Data Documentation

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

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

Ratio of double support period. Ratio is included in (0, 1). Double support period time is default_double_support_ratio*default_step_time.

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.

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.

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

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

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

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

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

Step height [m].

Step time [s].

Feedback gain when modifying footsteps based on Capture Point.

Gravitational acceleration [m/s^2].

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

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

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

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

Foot position offset[m] (rleg and lleg)

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

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

Whether modify footsteps based on Capture Point.

Number of optional finalize footsteps in goPos.

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

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

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

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

Stride limitation type.

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

Time offset [s] for swing trajectory by delay_hoffarbib_trajectory_generator.

Weight parameter for distance of final path of delay_hoffarbib_trajectory_generator (1.0 by default).

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.

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

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

Sequence of phase ratio of toe-off and heel-contact. Sum of toe_heel_phase_ratio should be 1.0.

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

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

Use stride limitation or not.

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

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 or not in toe-off heel-contact motion.

ZMP weight of RLEG, LLEG, RARM and LARM.


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