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

Stabilizer Parameters. More...

import"StabilizerService.idl";

Public Attributes

DblArray2 k_tpcc_p
 Feedback gain for ZMP tracking error (x,y) More...
 
DblArray2 k_tpcc_x
 Feedback gain for COG position tracking error (x,y) More...
 
DblArray2 k_brot_p
 Body posture control gain [rad/s] (roll, pitch). More...
 
DblArray2 k_brot_tc
 Time constant for body posture control [s] (roll, pitch). More...
 
DblArray2 eefm_k1
 Feedback gain for COG position tracking error (x,y) More...
 
DblArray2 eefm_k2
 Feedback gain for COG velocity tracking error (x,y) More...
 
DblArray2 eefm_k3
 Feedback gain for ZMP tracking error (x,y) More...
 
DblArray2 eefm_zmp_delay_time_const
 Time constant for stabilizer ZMP delay [s] (x,y) More...
 
DblArray2 eefm_ref_zmp_aux
 Auxiliary input for ZMP position [m] (x,y). This is used for delay model identification. More...
 
sequence< sequence< double, 3 > > eefm_rot_damping_gain
 Sequence of all end-effector rotation damping gain [Nm/(rad/s)] (r,p,y). More...
 
sequence< sequence< double, 3 > > eefm_rot_time_const
 Sequence of all end-effector rotation damping time constant [s] (r,p,y). More...
 
sequence< sequence< double, 3 > > eefm_pos_damping_gain
 Sequence of all end-effector position damping gain [N/(m/s)] (x,y,z). More...
 
sequence< sequence< double, 3 > > eefm_pos_time_const_support
 Sequence of all end-effector position damping time constant for double support phase [s] (x,y,z). More...
 
sequence< sequence< double, 3 > > eefm_swing_rot_spring_gain
 Sequence of all swing leg end-effector rotation spring gain (r,p,y). More...
 
sequence< sequence< double, 3 > > eefm_swing_rot_time_const
 Sequence of all swing leg end-effector rotation spring time constant [s] (r,p,y). More...
 
sequence< sequence< double, 3 > > eefm_swing_pos_spring_gain
 Sequence of all swing leg end-effector position spring gain (x,y,z). More...
 
sequence< sequence< double, 3 > > eefm_swing_pos_time_const
 Sequence of all swing leg end-effector position spring time constant [s] (x,y,z). More...
 
sequence< sequence< double, 3 > > eefm_ee_moment_limit
 Sequence of all end-effector end-effector-frame moment limit [Nm]. More...
 
sequence< double > eefm_pos_compensation_limit
 Sequence of all end-effector position compensation limit [m]. More...
 
sequence< double > eefm_rot_compensation_limit
 Sequence of all end-effector rot compensation limit [rad]. More...
 
double eefm_pos_time_const_swing
 End-effector position damping time constant for single support phase [s]. More...
 
double eefm_pos_transition_time
 Transition time for single=>double support phase gain interpolation [s]. More...
 
double eefm_pos_margin_time
 Margin for transition time for single=>double support phase gain interpolation [s]. More...
 
double eefm_leg_inside_margin
 Inside foot margine [m]. Distance between foot end effector position and foot inside edge. More...
 
double eefm_leg_outside_margin
 Outside foot margine [m]. Distance between foot end effector position and foot outside edge. More...
 
double eefm_leg_front_margin
 Front foot margine [m]. Distance between foot end effector position and foot front edge. More...
 
double eefm_leg_rear_margin
 Rear foot margine [m]. Distance between foot end effector position and foot rear edge. More...
 
DblArray2 eefm_body_attitude_control_gain
 Body attitude control gain [rad/s] (roll, pitch) for EEFM. More...
 
DblArray2 eefm_body_attitude_control_time_const
 Time constant for body attitude control [s] (roll, pitch) for EEFM. More...
 
double eefm_cogvel_cutoff_freq
 Cutoff frequency of LPF in calculation of COG velocity [Hz]. More...
 
double eefm_wrench_alpha_blending
 Blending parameter [0, 1] for wrench distribution. More...
 
double eefm_alpha_cutoff_freq
 Cutoff frequency of LPF in calculation of force moment distribution alpha ratio parameter [Hz]. More...
 
double eefm_gravitational_acceleration
 Gravitational acceleration [m/s^2] used in ST calculation. More...
 
double eefm_ee_pos_error_p_gain
 Pos error gain. More...
 
double eefm_ee_rot_error_p_gain
 Rot error gain. More...
 
double eefm_ee_error_cutoff_freq
 Pos rot error cutoff freq [Hz]. More...
 
sequence< SupportPolygonVerticeseefm_support_polygon_vertices_sequence
 Sequence of vertices for all end effectors assuming that the order is (rleg, lleg, rarm, larm) More...
 
boolean eefm_use_force_difference_control
 Use force difference control or each limb force control. True by default. More...
 
boolean eefm_use_swing_damping
 Use damping control for swing leg. More...
 
DblArray3 eefm_swing_damping_force_thre
 Swing damping control force threshold [N]. More...
 
DblArray3 eefm_swing_damping_moment_thre
 Swing damping control moment threshold [Nm]. More...
 
DblArray3 eefm_swing_rot_damping_gain
 Rotation damping gain for swing leg [Nm/(rad/s)] (r,p,y) More...
 
DblArray3 eefm_swing_pos_damping_gain
 Position damping gain for swing leg [N/(m/s)] (x,y,z) More...
 
sequence< sequence< double, 6 > > eefm_ee_forcemoment_distribution_weight
 Sequence of all end-effector force/moment distribution weight. More...
 
STAlgorithm st_algorithm
 Current Stabilizer algorithm. More...
 
ControllerMode controller_mode
 Current ControllerMode. More...
 
double transition_time
 Transition time [s] for start and stop Stabilizer. More...
 
BoolSequence is_ik_enable
 Bool sequence for all end effectors whether the end effector is used for limb IK. More...
 
BoolSequence is_feedback_control_enable
 Bool sequence for all end effectors whether the end effector is used for feedback control (currently damping control). More...
 
BoolSequence is_zmp_calc_enable
 Bool sequence for all end effectors whether the end effector is used for zmp calculation. More...
 
double cop_check_margin
 COP margin [m] from edges for COP checking. More...
 
DblArray4 cp_check_margin
 CP margin [m] (front, rear, inside, outside) More...
 
DblArray2 tilt_margin
 tilt margin [rad] (single support phase, double support phase) from reference floor More...
 
DblArray2 ref_capture_point
 ref_CP [m] (x,y) (foot_origin relative coordinate) More...
 
DblArray2 act_capture_point
 act_CP [m] (x,y) (foot_origin relative coordinate) More...
 
DblArray2 cp_offset
 CP_offset [m] (x,y) (foot_origin relative coordinate) More...
 
double contact_decision_threshold
 contact decision threshold [N] More...
 
sequence< sequence< double, 3 > > foot_origin_offset
 Foot origin position offset. More...
 
EmergencyCheckMode emergency_check_mode
 Emergency signal checking mode. More...
 
sequence< AutoBalancerService::Footstepend_effector_list
 
boolean is_estop_while_walking
 whether an emergency stop is used while walking More...
 
sequence< IKLimbParametersik_limb_parameters
 Sequence for all end-effectors' ik limb parameters. More...
 
boolean use_limb_stretch_avoidance
 Whether change root link height for avoiding limb stretch. More...
 
double limb_stretch_avoidance_time_const
 Limb stretch avoidance time constant [s]. More...
 
DblArray2 limb_stretch_avoidance_vlimit
 Root link height change limitation for avoiding limb stretch [m/s] (lower, upper) More...
 
sequence< double > limb_length_margin
 Sequence of limb length margin from max limb length [m]. More...
 
double detection_time_to_air
 Detection time whether is in air [s]. More...
 
DblArray2 root_rot_compensation_limit
 Limit of compensation for difference between ref-act root rot [rad]. More...
 
boolean use_zmp_truncation
 Whether truncate zmp according to foot support polygon or not. More...
 

Detailed Description

Stabilizer Parameters.

Member Data Documentation

◆ act_capture_point

DblArray2 OpenHRP::StabilizerService::stParam::act_capture_point

act_CP [m] (x,y) (foot_origin relative coordinate)

◆ contact_decision_threshold

double OpenHRP::StabilizerService::stParam::contact_decision_threshold

contact decision threshold [N]

◆ controller_mode

ControllerMode OpenHRP::StabilizerService::stParam::controller_mode

Current ControllerMode.

◆ cop_check_margin

double OpenHRP::StabilizerService::stParam::cop_check_margin

COP margin [m] from edges for COP checking.

◆ cp_check_margin

DblArray4 OpenHRP::StabilizerService::stParam::cp_check_margin

CP margin [m] (front, rear, inside, outside)

◆ cp_offset

DblArray2 OpenHRP::StabilizerService::stParam::cp_offset

CP_offset [m] (x,y) (foot_origin relative coordinate)

◆ detection_time_to_air

double OpenHRP::StabilizerService::stParam::detection_time_to_air

Detection time whether is in air [s].

◆ eefm_alpha_cutoff_freq

double OpenHRP::StabilizerService::stParam::eefm_alpha_cutoff_freq

Cutoff frequency of LPF in calculation of force moment distribution alpha ratio parameter [Hz].

◆ eefm_body_attitude_control_gain

DblArray2 OpenHRP::StabilizerService::stParam::eefm_body_attitude_control_gain

Body attitude control gain [rad/s] (roll, pitch) for EEFM.

◆ eefm_body_attitude_control_time_const

DblArray2 OpenHRP::StabilizerService::stParam::eefm_body_attitude_control_time_const

Time constant for body attitude control [s] (roll, pitch) for EEFM.

◆ eefm_cogvel_cutoff_freq

double OpenHRP::StabilizerService::stParam::eefm_cogvel_cutoff_freq

Cutoff frequency of LPF in calculation of COG velocity [Hz].

◆ eefm_ee_error_cutoff_freq

double OpenHRP::StabilizerService::stParam::eefm_ee_error_cutoff_freq

Pos rot error cutoff freq [Hz].

◆ eefm_ee_forcemoment_distribution_weight

sequence<sequence<double, 6> > OpenHRP::StabilizerService::stParam::eefm_ee_forcemoment_distribution_weight

Sequence of all end-effector force/moment distribution weight.

◆ eefm_ee_moment_limit

sequence<sequence<double, 3> > OpenHRP::StabilizerService::stParam::eefm_ee_moment_limit

Sequence of all end-effector end-effector-frame moment limit [Nm].

◆ eefm_ee_pos_error_p_gain

double OpenHRP::StabilizerService::stParam::eefm_ee_pos_error_p_gain

Pos error gain.

◆ eefm_ee_rot_error_p_gain

double OpenHRP::StabilizerService::stParam::eefm_ee_rot_error_p_gain

Rot error gain.

◆ eefm_gravitational_acceleration

double OpenHRP::StabilizerService::stParam::eefm_gravitational_acceleration

Gravitational acceleration [m/s^2] used in ST calculation.

◆ eefm_k1

DblArray2 OpenHRP::StabilizerService::stParam::eefm_k1

Feedback gain for COG position tracking error (x,y)

◆ eefm_k2

DblArray2 OpenHRP::StabilizerService::stParam::eefm_k2

Feedback gain for COG velocity tracking error (x,y)

◆ eefm_k3

DblArray2 OpenHRP::StabilizerService::stParam::eefm_k3

Feedback gain for ZMP tracking error (x,y)

◆ eefm_leg_front_margin

double OpenHRP::StabilizerService::stParam::eefm_leg_front_margin

Front foot margine [m]. Distance between foot end effector position and foot front edge.

◆ eefm_leg_inside_margin

double OpenHRP::StabilizerService::stParam::eefm_leg_inside_margin

Inside foot margine [m]. Distance between foot end effector position and foot inside edge.

◆ eefm_leg_outside_margin

double OpenHRP::StabilizerService::stParam::eefm_leg_outside_margin

Outside foot margine [m]. Distance between foot end effector position and foot outside edge.

◆ eefm_leg_rear_margin

double OpenHRP::StabilizerService::stParam::eefm_leg_rear_margin

Rear foot margine [m]. Distance between foot end effector position and foot rear edge.

◆ eefm_pos_compensation_limit

sequence<double> OpenHRP::StabilizerService::stParam::eefm_pos_compensation_limit

Sequence of all end-effector position compensation limit [m].

◆ eefm_pos_damping_gain

sequence<sequence<double, 3> > OpenHRP::StabilizerService::stParam::eefm_pos_damping_gain

Sequence of all end-effector position damping gain [N/(m/s)] (x,y,z).

◆ eefm_pos_margin_time

double OpenHRP::StabilizerService::stParam::eefm_pos_margin_time

Margin for transition time for single=>double support phase gain interpolation [s].

◆ eefm_pos_time_const_support

sequence<sequence<double, 3> > OpenHRP::StabilizerService::stParam::eefm_pos_time_const_support

Sequence of all end-effector position damping time constant for double support phase [s] (x,y,z).

◆ eefm_pos_time_const_swing

double OpenHRP::StabilizerService::stParam::eefm_pos_time_const_swing

End-effector position damping time constant for single support phase [s].

◆ eefm_pos_transition_time

double OpenHRP::StabilizerService::stParam::eefm_pos_transition_time

Transition time for single=>double support phase gain interpolation [s].

◆ eefm_ref_zmp_aux

DblArray2 OpenHRP::StabilizerService::stParam::eefm_ref_zmp_aux

Auxiliary input for ZMP position [m] (x,y). This is used for delay model identification.

◆ eefm_rot_compensation_limit

sequence<double> OpenHRP::StabilizerService::stParam::eefm_rot_compensation_limit

Sequence of all end-effector rot compensation limit [rad].

◆ eefm_rot_damping_gain

sequence<sequence<double, 3> > OpenHRP::StabilizerService::stParam::eefm_rot_damping_gain

Sequence of all end-effector rotation damping gain [Nm/(rad/s)] (r,p,y).

◆ eefm_rot_time_const

sequence<sequence<double, 3> > OpenHRP::StabilizerService::stParam::eefm_rot_time_const

Sequence of all end-effector rotation damping time constant [s] (r,p,y).

◆ eefm_support_polygon_vertices_sequence

sequence< SupportPolygonVertices > OpenHRP::StabilizerService::stParam::eefm_support_polygon_vertices_sequence

Sequence of vertices for all end effectors assuming that the order is (rleg, lleg, rarm, larm)

◆ eefm_swing_damping_force_thre

DblArray3 OpenHRP::StabilizerService::stParam::eefm_swing_damping_force_thre

Swing damping control force threshold [N].

◆ eefm_swing_damping_moment_thre

DblArray3 OpenHRP::StabilizerService::stParam::eefm_swing_damping_moment_thre

Swing damping control moment threshold [Nm].

◆ eefm_swing_pos_damping_gain

DblArray3 OpenHRP::StabilizerService::stParam::eefm_swing_pos_damping_gain

Position damping gain for swing leg [N/(m/s)] (x,y,z)

◆ eefm_swing_pos_spring_gain

sequence<sequence<double, 3> > OpenHRP::StabilizerService::stParam::eefm_swing_pos_spring_gain

Sequence of all swing leg end-effector position spring gain (x,y,z).

◆ eefm_swing_pos_time_const

sequence<sequence<double, 3> > OpenHRP::StabilizerService::stParam::eefm_swing_pos_time_const

Sequence of all swing leg end-effector position spring time constant [s] (x,y,z).

◆ eefm_swing_rot_damping_gain

DblArray3 OpenHRP::StabilizerService::stParam::eefm_swing_rot_damping_gain

Rotation damping gain for swing leg [Nm/(rad/s)] (r,p,y)

◆ eefm_swing_rot_spring_gain

sequence<sequence<double, 3> > OpenHRP::StabilizerService::stParam::eefm_swing_rot_spring_gain

Sequence of all swing leg end-effector rotation spring gain (r,p,y).

◆ eefm_swing_rot_time_const

sequence<sequence<double, 3> > OpenHRP::StabilizerService::stParam::eefm_swing_rot_time_const

Sequence of all swing leg end-effector rotation spring time constant [s] (r,p,y).

◆ eefm_use_force_difference_control

boolean OpenHRP::StabilizerService::stParam::eefm_use_force_difference_control

Use force difference control or each limb force control. True by default.

◆ eefm_use_swing_damping

boolean OpenHRP::StabilizerService::stParam::eefm_use_swing_damping

Use damping control for swing leg.

◆ eefm_wrench_alpha_blending

double OpenHRP::StabilizerService::stParam::eefm_wrench_alpha_blending

Blending parameter [0, 1] for wrench distribution.

◆ eefm_zmp_delay_time_const

DblArray2 OpenHRP::StabilizerService::stParam::eefm_zmp_delay_time_const

Time constant for stabilizer ZMP delay [s] (x,y)

◆ emergency_check_mode

EmergencyCheckMode OpenHRP::StabilizerService::stParam::emergency_check_mode

Emergency signal checking mode.

◆ end_effector_list

sequence<AutoBalancerService::Footstep> OpenHRP::StabilizerService::stParam::end_effector_list

◆ foot_origin_offset

sequence< sequence<double, 3> > OpenHRP::StabilizerService::stParam::foot_origin_offset

Foot origin position offset.

◆ ik_limb_parameters

sequence<IKLimbParameters> OpenHRP::StabilizerService::stParam::ik_limb_parameters

Sequence for all end-effectors' ik limb parameters.

◆ is_estop_while_walking

boolean OpenHRP::StabilizerService::stParam::is_estop_while_walking

whether an emergency stop is used while walking

◆ is_feedback_control_enable

BoolSequence OpenHRP::StabilizerService::stParam::is_feedback_control_enable

Bool sequence for all end effectors whether the end effector is used for feedback control (currently damping control).

◆ is_ik_enable

BoolSequence OpenHRP::StabilizerService::stParam::is_ik_enable

Bool sequence for all end effectors whether the end effector is used for limb IK.

◆ is_zmp_calc_enable

BoolSequence OpenHRP::StabilizerService::stParam::is_zmp_calc_enable

Bool sequence for all end effectors whether the end effector is used for zmp calculation.

◆ k_brot_p

DblArray2 OpenHRP::StabilizerService::stParam::k_brot_p

Body posture control gain [rad/s] (roll, pitch).

◆ k_brot_tc

DblArray2 OpenHRP::StabilizerService::stParam::k_brot_tc

Time constant for body posture control [s] (roll, pitch).

◆ k_tpcc_p

DblArray2 OpenHRP::StabilizerService::stParam::k_tpcc_p

Feedback gain for ZMP tracking error (x,y)

◆ k_tpcc_x

DblArray2 OpenHRP::StabilizerService::stParam::k_tpcc_x

Feedback gain for COG position tracking error (x,y)

◆ limb_length_margin

sequence<double> OpenHRP::StabilizerService::stParam::limb_length_margin

Sequence of limb length margin from max limb length [m].

◆ limb_stretch_avoidance_time_const

double OpenHRP::StabilizerService::stParam::limb_stretch_avoidance_time_const

Limb stretch avoidance time constant [s].

◆ limb_stretch_avoidance_vlimit

DblArray2 OpenHRP::StabilizerService::stParam::limb_stretch_avoidance_vlimit

Root link height change limitation for avoiding limb stretch [m/s] (lower, upper)

◆ ref_capture_point

DblArray2 OpenHRP::StabilizerService::stParam::ref_capture_point

ref_CP [m] (x,y) (foot_origin relative coordinate)

◆ root_rot_compensation_limit

DblArray2 OpenHRP::StabilizerService::stParam::root_rot_compensation_limit

Limit of compensation for difference between ref-act root rot [rad].

◆ st_algorithm

STAlgorithm OpenHRP::StabilizerService::stParam::st_algorithm

Current Stabilizer algorithm.

◆ tilt_margin

DblArray2 OpenHRP::StabilizerService::stParam::tilt_margin

tilt margin [rad] (single support phase, double support phase) from reference floor

◆ transition_time

double OpenHRP::StabilizerService::stParam::transition_time

Transition time [s] for start and stop Stabilizer.

◆ use_limb_stretch_avoidance

boolean OpenHRP::StabilizerService::stParam::use_limb_stretch_avoidance

Whether change root link height for avoiding limb stretch.

◆ use_zmp_truncation

boolean OpenHRP::StabilizerService::stParam::use_zmp_truncation

Whether truncate zmp according to foot support polygon or not.


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