Basic RT components and utilities  315.7.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)
DblArray2 k_tpcc_x
 Feedback gain for COG position tracking error (x,y)
DblArray2 k_brot_p
 Body posture control gain [rad/s] (roll, pitch).
DblArray2 k_brot_tc
 Time constant for body posture control [s] (roll, pitch).
DblArray2 k_run_b
DblArray2 d_run_b
DblArray2 tdfke
DblArray2 tdftc
double k_run_x
double k_run_y
double d_run_x
double d_run_y
DblArray2 eefm_k1
 Feedback gain for COG position tracking error (x,y)
DblArray2 eefm_k2
 Feedback gain for COG velocity tracking error (x,y)
DblArray2 eefm_k3
 Feedback gain for ZMP tracking error (x,y)
DblArray2 eefm_zmp_delay_time_const
 Time constant for stabilizer ZMP delay [s] (x,y)
DblArray2 eefm_ref_zmp_aux
 Auxiliary input for ZMP position [m] (x,y). This is used for delay model identification.
double eefm_rot_damping_gain
 Foot rotation damping gain [Nm/(rad/s)].
double eefm_rot_time_const
 Foot rotation damping time constant [s].
DblArray3 eefm_pos_damping_gain
 Foot position damping gain [N/(m/s)].
DblArray3 eefm_pos_time_const_support
 Foot position damping time constant for double support phase [s].
double eefm_pos_time_const_swing
 Foot position damping time constant for single support phase [s].
double eefm_pos_transition_time
 Transition time for single=>double support phase gain interpolation [s].
double eefm_pos_margin_time
 Margin for transition time for single=>double support phase gain interpolation [s].
double eefm_leg_inside_margin
 Inside foot margine [m]. Distance between foot end effector position and foot inside edge.
double eefm_leg_outside_margin
 Outside foot margine [m]. Distance between foot end effector position and foot outside edge.
double eefm_leg_front_margin
 Front foot margine [m]. Distance between foot end effector position and foot front edge.
double eefm_leg_rear_margin
 Rear foot margine [m]. Distance between foot end effector position and foot rear edge.
DblArray2 eefm_body_attitude_control_gain
 Body attitude control gain [rad/s] (roll, pitch) for EEFM.
DblArray2 eefm_body_attitude_control_time_const
 Time constant for body attitude control [s] (roll, pitch) for EEFM.
double eefm_cogvel_cutoff_freq
 Cutoff frequency of LPF in calculation of COG velocity [Hz].
double eefm_wrench_alpha_blending
 Blending parameter [0, 1] for wrench distribution.
double eefm_alpha_cutoff_freq
 Cutoff frequency of LPF in calculation of force moment distribution alpha ratio parameter [Hz].
double eefm_gravitational_acceleration
 Gravitational acceleration [m/s^2] used in ST calculation.
double eefm_ee_pos_error_p_gain
 Pos error gain.
double eefm_ee_rot_error_p_gain
 Rot error gain.
double eefm_ee_error_cutoff_freq
 Pos rot error cutoff freq [Hz].
BoolSequence is_ik_enable
 Is ik enable.
STAlgorithm st_algorithm
 Current Stabilizer algorithm.
ControllerMode controller_mode
 Current ControllerMode.
double transition_time
 Transition time [s] for start and stop Stabilizer.
double cop_check_margin
 COP margin [m] from edges for COP checking.
double cp_check_margin
 CP margin [m].
double contact_decision_threshold
 contact decision threshold [N]
sequence< sequence< double, 3 > > foot_origin_offset
 Foot origin position offset.
EmergencyCheckMode emergency_check_mode
 Emergency signal checking mode.

Detailed Description

Stabilizer Parameters.

Member Data Documentation

double OpenHRP::StabilizerService::stParam::contact_decision_threshold

contact decision threshold [N]

ControllerMode OpenHRP::StabilizerService::stParam::controller_mode

Current ControllerMode.

double OpenHRP::StabilizerService::stParam::cop_check_margin

COP margin [m] from edges for COP checking.

double OpenHRP::StabilizerService::stParam::cp_check_margin

CP margin [m].

DblArray2 OpenHRP::StabilizerService::stParam::d_run_b
double OpenHRP::StabilizerService::stParam::d_run_x
double OpenHRP::StabilizerService::stParam::d_run_y
double OpenHRP::StabilizerService::stParam::eefm_alpha_cutoff_freq

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

DblArray2 OpenHRP::StabilizerService::stParam::eefm_body_attitude_control_gain

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

DblArray2 OpenHRP::StabilizerService::stParam::eefm_body_attitude_control_time_const

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

double OpenHRP::StabilizerService::stParam::eefm_cogvel_cutoff_freq

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

double OpenHRP::StabilizerService::stParam::eefm_ee_error_cutoff_freq

Pos rot error cutoff freq [Hz].

double OpenHRP::StabilizerService::stParam::eefm_ee_pos_error_p_gain

Pos error gain.

double OpenHRP::StabilizerService::stParam::eefm_ee_rot_error_p_gain

Rot error gain.

double OpenHRP::StabilizerService::stParam::eefm_gravitational_acceleration

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

DblArray2 OpenHRP::StabilizerService::stParam::eefm_k1

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

DblArray2 OpenHRP::StabilizerService::stParam::eefm_k2

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

DblArray2 OpenHRP::StabilizerService::stParam::eefm_k3

Feedback gain for ZMP tracking error (x,y)

double OpenHRP::StabilizerService::stParam::eefm_leg_front_margin

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

double OpenHRP::StabilizerService::stParam::eefm_leg_inside_margin

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

double OpenHRP::StabilizerService::stParam::eefm_leg_outside_margin

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

double OpenHRP::StabilizerService::stParam::eefm_leg_rear_margin

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

DblArray3 OpenHRP::StabilizerService::stParam::eefm_pos_damping_gain

Foot position damping gain [N/(m/s)].

double OpenHRP::StabilizerService::stParam::eefm_pos_margin_time

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

DblArray3 OpenHRP::StabilizerService::stParam::eefm_pos_time_const_support

Foot position damping time constant for double support phase [s].

double OpenHRP::StabilizerService::stParam::eefm_pos_time_const_swing

Foot position damping time constant for single support phase [s].

double OpenHRP::StabilizerService::stParam::eefm_pos_transition_time

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

DblArray2 OpenHRP::StabilizerService::stParam::eefm_ref_zmp_aux

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

double OpenHRP::StabilizerService::stParam::eefm_rot_damping_gain

Foot rotation damping gain [Nm/(rad/s)].

double OpenHRP::StabilizerService::stParam::eefm_rot_time_const

Foot rotation damping time constant [s].

double OpenHRP::StabilizerService::stParam::eefm_wrench_alpha_blending

Blending parameter [0, 1] for wrench distribution.

DblArray2 OpenHRP::StabilizerService::stParam::eefm_zmp_delay_time_const

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

EmergencyCheckMode OpenHRP::StabilizerService::stParam::emergency_check_mode

Emergency signal checking mode.

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

Foot origin position offset.

BoolSequence OpenHRP::StabilizerService::stParam::is_ik_enable

Is ik enable.

DblArray2 OpenHRP::StabilizerService::stParam::k_brot_p

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

DblArray2 OpenHRP::StabilizerService::stParam::k_brot_tc

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

DblArray2 OpenHRP::StabilizerService::stParam::k_run_b
double OpenHRP::StabilizerService::stParam::k_run_x
double OpenHRP::StabilizerService::stParam::k_run_y
DblArray2 OpenHRP::StabilizerService::stParam::k_tpcc_p

Feedback gain for ZMP tracking error (x,y)

DblArray2 OpenHRP::StabilizerService::stParam::k_tpcc_x

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

STAlgorithm OpenHRP::StabilizerService::stParam::st_algorithm

Current Stabilizer algorithm.

DblArray2 OpenHRP::StabilizerService::stParam::tdfke
DblArray2 OpenHRP::StabilizerService::stParam::tdftc
double OpenHRP::StabilizerService::stParam::transition_time

Transition time [s] for start and stop Stabilizer.


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