Basic RT components and utilities
315.12.1
|
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 | 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. | |
sequence< sequence< double, 3 > > | eefm_rot_damping_gain |
Sequence of all end-effector rotation damping gain [Nm/(rad/s)] (r,p,y). | |
sequence< sequence< double, 3 > > | eefm_rot_time_const |
Sequence of all end-effector rotation damping time constant [s] (r,p,y). | |
sequence< sequence< double, 3 > > | eefm_pos_damping_gain |
Sequence of all end-effector position damping gain [N/(m/s)] (x,y,z). | |
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). | |
sequence< sequence< double, 3 > > | eefm_swing_rot_spring_gain |
Sequence of all swing leg end-effector rotation spring gain (r,p,y). | |
sequence< sequence< double, 3 > > | eefm_swing_rot_time_const |
Sequence of all swing leg end-effector rotation spring time constant [s] (r,p,y). | |
sequence< sequence< double, 3 > > | eefm_swing_pos_spring_gain |
Sequence of all swing leg end-effector position spring gain (x,y,z). | |
sequence< sequence< double, 3 > > | eefm_swing_pos_time_const |
Sequence of all swing leg end-effector position spring time constant [s] (x,y,z). | |
sequence< sequence< double, 3 > > | eefm_ee_moment_limit |
Sequence of all end-effector end-effector-frame moment limit [Nm]. | |
sequence< double > | eefm_pos_compensation_limit |
Sequence of all end-effector position compensation limit [m]. | |
sequence< double > | eefm_rot_compensation_limit |
Sequence of all end-effector rot compensation limit [rad]. | |
double | eefm_pos_time_const_swing |
End-effector 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]. | |
sequence< SupportPolygonVertices > | eefm_support_polygon_vertices_sequence |
Sequence of vertices for all end effectors. | |
boolean | eefm_use_force_difference_control |
Use force difference control or each limb force control. True by default. | |
boolean | eefm_use_swing_damping |
Use damping control for swing leg. | |
DblArray3 | eefm_swing_damping_force_thre |
Swing damping control force threshold [N]. | |
DblArray3 | eefm_swing_damping_moment_thre |
Swing damping control moment threshold [Nm]. | |
DblArray3 | eefm_swing_rot_damping_gain |
Rotation damping gain for swing leg [Nm/(rad/s)] (r,p,y) | |
DblArray3 | eefm_swing_pos_damping_gain |
Position damping gain for swing leg [N/(m/s)] (x,y,z) | |
sequence< sequence< double, 6 > > | eefm_ee_forcemoment_distribution_weight |
Sequence of all end-effector force/moment distribution weight. | |
STAlgorithm | st_algorithm |
Current Stabilizer algorithm. | |
ControllerMode | controller_mode |
Current ControllerMode. | |
double | transition_time |
Transition time [s] for start and stop Stabilizer. | |
BoolSequence | is_ik_enable |
Bool sequence for all end effectors whether the end effector is used for limb IK. | |
BoolSequence | is_feedback_control_enable |
Bool sequence for all end effectors whether the end effector is used for feedback control (currently damping control). | |
BoolSequence | is_zmp_calc_enable |
Bool sequence for all end effectors whether the end effector is used for zmp calculation. | |
double | cop_check_margin |
COP margin [m] from edges for COP checking. | |
DblArray4 | cp_check_margin |
CP margin [m] (front, rear, inside, outside) | |
DblArray2 | tilt_margin |
tilt margin [rad] (single support phase, double support phase) from reference floor | |
DblArray2 | ref_capture_point |
ref_CP [m] (x,y) (foot_origin relative coordinate) | |
DblArray2 | act_capture_point |
act_CP [m] (x,y) (foot_origin relative coordinate) | |
DblArray2 | cp_offset |
CP_offset [m] (x,y) (foot_origin relative coordinate) | |
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. | |
sequence < AutoBalancerService::Footstep > | end_effector_list |
boolean | is_estop_while_walking |
whether an emergency stop is used while walking | |
sequence< IKLimbParameters > | ik_limb_parameters |
Sequence for all end-effectors' ik limb parameters. | |
boolean | use_limb_stretch_avoidance |
Whether change root link height for avoiding limb stretch. | |
double | limb_stretch_avoidance_time_const |
Limb stretch avoidance time constant [s]. | |
DblArray2 | limb_stretch_avoidance_vlimit |
Root link height change limitation for avoiding limb stretch [m/s] (lower, upper) | |
sequence< double > | limb_length_margin |
Sequence of limb length margin from max limb length [m]. | |
double | detection_time_to_air |
Detection time whether is in air [s]. |
Stabilizer Parameters.
act_CP [m] (x,y) (foot_origin relative coordinate)
contact decision threshold [N]
Current ControllerMode.
COP margin [m] from edges for COP checking.
CP margin [m] (front, rear, inside, outside)
CP_offset [m] (x,y) (foot_origin relative coordinate)
Detection time whether is in air [s].
Cutoff frequency of LPF in calculation of force moment distribution alpha ratio parameter [Hz].
Body attitude control gain [rad/s] (roll, pitch) for EEFM.
Time constant for body attitude control [s] (roll, pitch) for EEFM.
Cutoff frequency of LPF in calculation of COG velocity [Hz].
Pos rot error cutoff freq [Hz].
sequence<sequence<double, 6> > OpenHRP::StabilizerService::stParam::eefm_ee_forcemoment_distribution_weight |
Sequence of all end-effector force/moment distribution weight.
sequence<sequence<double, 3> > OpenHRP::StabilizerService::stParam::eefm_ee_moment_limit |
Sequence of all end-effector end-effector-frame moment limit [Nm].
Pos error gain.
Rot error gain.
Gravitational acceleration [m/s^2] used in ST calculation.
Feedback gain for COG position tracking error (x,y)
Feedback gain for COG velocity tracking error (x,y)
Feedback gain for ZMP tracking error (x,y)
Front foot margine [m]. Distance between foot end effector position and foot front edge.
Inside foot margine [m]. Distance between foot end effector position and foot inside edge.
Outside foot margine [m]. Distance between foot end effector position and foot outside edge.
Rear foot margine [m]. Distance between foot end effector position and foot rear edge.
sequence<double> OpenHRP::StabilizerService::stParam::eefm_pos_compensation_limit |
Sequence of all end-effector position compensation limit [m].
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).
Margin for transition time for single=>double support phase gain interpolation [s].
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).
End-effector position damping time constant for single support phase [s].
Transition time for single=>double support phase gain interpolation [s].
Auxiliary input for ZMP position [m] (x,y). This is used for delay model identification.
sequence<double> OpenHRP::StabilizerService::stParam::eefm_rot_compensation_limit |
Sequence of all end-effector rot compensation limit [rad].
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).
sequence<sequence<double, 3> > OpenHRP::StabilizerService::stParam::eefm_rot_time_const |
Sequence of all end-effector rotation damping time constant [s] (r,p,y).
sequence< SupportPolygonVertices > OpenHRP::StabilizerService::stParam::eefm_support_polygon_vertices_sequence |
Sequence of vertices for all end effectors.
Swing damping control force threshold [N].
Swing damping control moment threshold [Nm].
Position damping gain for swing leg [N/(m/s)] (x,y,z)
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).
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).
Rotation damping gain for swing leg [Nm/(rad/s)] (r,p,y)
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).
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).
Use force difference control or each limb force control. True by default.
Use damping control for swing leg.
Blending parameter [0, 1] for wrench distribution.
Time constant for stabilizer ZMP delay [s] (x,y)
Emergency signal checking mode.
sequence< sequence<double, 3> > OpenHRP::StabilizerService::stParam::foot_origin_offset |
Foot origin position offset.
Sequence for all end-effectors' ik limb parameters.
whether an emergency stop is used while walking
Bool sequence for all end effectors whether the end effector is used for feedback control (currently damping control).
Bool sequence for all end effectors whether the end effector is used for limb IK.
Bool sequence for all end effectors whether the end effector is used for zmp calculation.
Body posture control gain [rad/s] (roll, pitch).
Time constant for body posture control [s] (roll, pitch).
Feedback gain for ZMP tracking error (x,y)
Feedback gain for COG position tracking error (x,y)
sequence<double> OpenHRP::StabilizerService::stParam::limb_length_margin |
Sequence of limb length margin from max limb length [m].
Limb stretch avoidance time constant [s].
Root link height change limitation for avoiding limb stretch [m/s] (lower, upper)
ref_CP [m] (x,y) (foot_origin relative coordinate)
Current Stabilizer algorithm.
tilt margin [rad] (single support phase, double support phase) from reference floor
Transition time [s] for start and stop Stabilizer.
Whether change root link height for avoiding limb stretch.