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

Parameters for AutoBalancer. More...

import"AutoBalancerService.idl";

Collaboration diagram for OpenHRP::AutoBalancerService::AutoBalancerParam:
Collaboration graph
[legend]

Public Attributes

sequence< DblSequence3default_zmp_offsets
 ZMP offset vectors[m] for rleg and lleg (<-please set by this order) More...
 
double move_base_gain
 
ControllerMode controller_mode
 
UseForceMode use_force_mode
 
boolean graspless_manip_mode
 
string graspless_manip_arm
 
DblArray3 graspless_manip_p_gain
 
DblArray3 graspless_manip_reference_trans_pos
 
DblArray4 graspless_manip_reference_trans_rot
 
double transition_time
 Transition time [s] for start and stop AutoBalancer. More...
 
double zmp_transition_time
 Transition time [s] for default_zmp_offsets. More...
 
double adjust_footstep_transition_time
 Transition time [s] for adjust foot step. More...
 
StrSequence leg_names
 
boolean has_ik_failed
 Flag for inverse kinematics (IK). If true, IK has failed before. More...
 
double pos_ik_thre
 IK position threshold [m]. More...
 
double rot_ik_thre
 IK rotation threshold [rad]. More...
 
boolean is_hand_fix_mode
 Flag for fix hand while walking. More...
 
sequence< Footstepend_effector_list
 
GaitType default_gait_type
 Default GaitType. 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...
 
string additional_force_applied_link_name
 Name of additional force applied link for MODE_REF_FORCE_WITH_FOOT for MODE_REF_FORCE_RFU_EXT_MOMENT. Additional force is applied to the point without force sensors, such as torso. More...
 
DblArray3 additional_force_applied_point_offset
 Link local offset[m] of force applied point for MODE_REF_FORCE_WITH_FOOT. This is local value in the link frame specified by "additional_force_applied_link_name". Zero by default. More...
 

Detailed Description

Parameters for AutoBalancer.

Member Data Documentation

◆ additional_force_applied_link_name

string OpenHRP::AutoBalancerService::AutoBalancerParam::additional_force_applied_link_name

Name of additional force applied link for MODE_REF_FORCE_WITH_FOOT for MODE_REF_FORCE_RFU_EXT_MOMENT. Additional force is applied to the point without force sensors, such as torso.

◆ additional_force_applied_point_offset

DblArray3 OpenHRP::AutoBalancerService::AutoBalancerParam::additional_force_applied_point_offset

Link local offset[m] of force applied point for MODE_REF_FORCE_WITH_FOOT. This is local value in the link frame specified by "additional_force_applied_link_name". Zero by default.

◆ adjust_footstep_transition_time

double OpenHRP::AutoBalancerService::AutoBalancerParam::adjust_footstep_transition_time

Transition time [s] for adjust foot step.

◆ controller_mode

ControllerMode OpenHRP::AutoBalancerService::AutoBalancerParam::controller_mode

◆ default_gait_type

GaitType OpenHRP::AutoBalancerService::AutoBalancerParam::default_gait_type

Default GaitType.

◆ default_zmp_offsets

sequence<DblSequence3> OpenHRP::AutoBalancerService::AutoBalancerParam::default_zmp_offsets

ZMP offset vectors[m] for rleg and lleg (<-please set by this order)

◆ end_effector_list

sequence<Footstep> OpenHRP::AutoBalancerService::AutoBalancerParam::end_effector_list

◆ graspless_manip_arm

string OpenHRP::AutoBalancerService::AutoBalancerParam::graspless_manip_arm

◆ graspless_manip_mode

boolean OpenHRP::AutoBalancerService::AutoBalancerParam::graspless_manip_mode

◆ graspless_manip_p_gain

DblArray3 OpenHRP::AutoBalancerService::AutoBalancerParam::graspless_manip_p_gain

◆ graspless_manip_reference_trans_pos

DblArray3 OpenHRP::AutoBalancerService::AutoBalancerParam::graspless_manip_reference_trans_pos

◆ graspless_manip_reference_trans_rot

DblArray4 OpenHRP::AutoBalancerService::AutoBalancerParam::graspless_manip_reference_trans_rot

◆ has_ik_failed

boolean OpenHRP::AutoBalancerService::AutoBalancerParam::has_ik_failed

Flag for inverse kinematics (IK). If true, IK has failed before.

◆ ik_limb_parameters

sequence<IKLimbParameters> OpenHRP::AutoBalancerService::AutoBalancerParam::ik_limb_parameters

Sequence for all end-effectors' ik limb parameters.

◆ is_hand_fix_mode

boolean OpenHRP::AutoBalancerService::AutoBalancerParam::is_hand_fix_mode

Flag for fix hand while walking.

◆ leg_names

StrSequence OpenHRP::AutoBalancerService::AutoBalancerParam::leg_names

◆ limb_length_margin

sequence<double> OpenHRP::AutoBalancerService::AutoBalancerParam::limb_length_margin

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

◆ limb_stretch_avoidance_time_const

double OpenHRP::AutoBalancerService::AutoBalancerParam::limb_stretch_avoidance_time_const

Limb stretch avoidance time constant [s].

◆ limb_stretch_avoidance_vlimit

DblArray2 OpenHRP::AutoBalancerService::AutoBalancerParam::limb_stretch_avoidance_vlimit

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

◆ move_base_gain

double OpenHRP::AutoBalancerService::AutoBalancerParam::move_base_gain

◆ pos_ik_thre

double OpenHRP::AutoBalancerService::AutoBalancerParam::pos_ik_thre

IK position threshold [m].

◆ rot_ik_thre

double OpenHRP::AutoBalancerService::AutoBalancerParam::rot_ik_thre

IK rotation threshold [rad].

◆ transition_time

double OpenHRP::AutoBalancerService::AutoBalancerParam::transition_time

Transition time [s] for start and stop AutoBalancer.

◆ use_force_mode

UseForceMode OpenHRP::AutoBalancerService::AutoBalancerParam::use_force_mode

◆ use_limb_stretch_avoidance

boolean OpenHRP::AutoBalancerService::AutoBalancerParam::use_limb_stretch_avoidance

Whether change root link height for avoiding limb stretch.

◆ zmp_transition_time

double OpenHRP::AutoBalancerService::AutoBalancerParam::zmp_transition_time

Transition time [s] for default_zmp_offsets.


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