activate(RTC::UniqueId ec_id) | RTC::RTObject_impl | |
addConfigurationParamListener(ConfigurationParamListenerType type, ConfigurationParamListener *listener, bool autoclean=true) | RTC::RTObject_impl | |
addConfigurationParamListener(ConfigurationParamListenerType listener_type, Listener &obj, void(Listener::*memfunc)(const char *, const char *)) | RTC::RTObject_impl | |
addConfigurationSetListener(ConfigurationSetListenerType type, ConfigurationSetListener *listener, bool autoclean=true) | RTC::RTObject_impl | |
addConfigurationSetListener(ConfigurationSetListenerType listener_type, Listener &obj, void(Listener::*memfunc)(const coil::Properties &config_set)) | RTC::RTObject_impl | |
addConfigurationSetNameListener(ConfigurationSetNameListenerType type, ConfigurationSetNameListener *listener, bool autoclean=true) | RTC::RTObject_impl | |
addConfigurationSetNameListener(ConfigurationSetNameListenerType type, Listener &obj, void(Listener::*memfunc)(const char *)) | RTC::RTObject_impl | |
addExecutionContextActionListener(ECActionListenerType listener_type, ECActionListener *listener, bool autoclean=true) | RTC::RTObject_impl | |
addExecutionContextActionListener(ECActionListenerType listener_type, Listener &obj, void(Listener::*memfunc)(UniqueId)) | RTC::RTObject_impl | |
addInPort(const char *name, InPortBase &inport) | RTC::RTObject_impl | |
additional_force_applied_link | AutoBalancer | private |
additional_force_applied_point_offset | AutoBalancer | private |
addOutPort(const char *name, OutPortBase &outport) | RTC::RTObject_impl | |
addPort(PortBase &port) | RTC::RTObject_impl | |
addPort(PortService_ptr port) | RTC::RTObject_impl | |
addPort(CorbaPort &port) | RTC::RTObject_impl | |
addPortActionListener(PortActionListenerType listener_type, PortActionListener *listener, bool autoclean=true) | RTC::RTObject_impl | |
addPortActionListener(PortActionListenerType listener_type, Listener &obj, void(Listener::*memfunc)(const RTC::PortProfile &)) | RTC::RTObject_impl | |
addPortConnectListener(PortConnectListenerType listener_type, PortConnectListener *listener, bool autoclean=true) | RTC::RTObject_impl | |
addPortConnectListener(PortConnectListenerType listener_type, Listener &obj, void(Listener::*memfunc)(const char *, ConnectorProfile &)) | RTC::RTObject_impl | |
addPortConnectRetListener(PortConnectRetListenerType listener_type, PortConnectRetListener *listener, bool autoclean=true) | RTC::RTObject_impl | |
addPortConnectRetListener(PortConnectRetListenerType listener_type, Listener &obj, void(Listener::*memfunc)(const char *, ConnectorProfile &, ReturnCode_t)) | RTC::RTObject_impl | |
addPostComponentActionListener(PostComponentActionListenerType listener_type, PostComponentActionListener *listener, bool autoclean=true) | RTC::RTObject_impl | |
addPostComponentActionListener(PostCompActionListenerType listener_type, Listener &obj, void(Listener::*memfunc)(UniqueId ec_id, ReturnCode_t ret)) | RTC::RTObject_impl | |
addPreComponentActionListener(PreComponentActionListenerType listener_type, PreComponentActionListener *listener, bool autoclean=true) | RTC::RTObject_impl | |
addPreComponentActionListener(PreCompActionListenerType listener_type, Listener &obj, void(Listener::*memfunc)(UniqueId ec_id)) | RTC::RTObject_impl | |
addSdoServiceConsumer(const SDOPackage::ServiceProfile &prof) | RTC::RTObject_impl | |
addSdoServiceProvider(const SDOPackage::ServiceProfile &prof, SdoServiceProviderBase *provider) | RTC::RTObject_impl | |
adjust_footstep_interpolator | AutoBalancer | private |
adjust_footstep_transition_time | AutoBalancer | private |
adjustFootSteps(const OpenHRP::AutoBalancerService::Footstep &rfootstep, const OpenHRP::AutoBalancerService::Footstep &lfootstep) | AutoBalancer | |
attach_context(ExecutionContext_ptr exec_context) | RTC::RTObject_impl | |
AutoBalancer(RTC::Manager *manager) | AutoBalancer | |
bindContext(ExecutionContext_ptr exec_context) | RTC::RTObject_impl | |
bindParameter(const char *param_name, VarType &var, const char *def_val, bool(*trans)(VarType &, const char *)=coil::stringTo) | RTC::RTObject_impl | |
BIPED enum value | AutoBalancer | private |
calc_inital_support_legs(const double &y, std::vector< rats::coordinates > &initial_support_legs_coords, std::vector< rats::leg_type > &initial_support_legs, rats::coordinates &start_ref_coords) | AutoBalancer | private |
calc_static_balance_point_from_forces(hrp::Vector3 &sb_point, const hrp::Vector3 &tmpcog, const double ref_com_height) | AutoBalancer | private |
calc_vel_from_hand_error(const rats::coordinates &tmp_fix_coords) | AutoBalancer | private |
calcFixCoordsForAdjustFootstep(rats::coordinates &tmp_fix_coords) | AutoBalancer | private |
calcFootMidPosUsingZMPWeightMap() | AutoBalancer | private |
calcReferenceJointAnglesForIK() | AutoBalancer | private |
calculateOutputRefForces() | AutoBalancer | private |
contact_states_index_map | AutoBalancer | private |
control_mode | AutoBalancer | private |
copyRatscoords2Footstep(OpenHRP::AutoBalancerService::Footstep &out_fs, const rats::coordinates &in_fs) | AutoBalancer | private |
CRAWL enum value | AutoBalancer | private |
d_pos_z_root | AutoBalancer | private |
DataFlowComponentBase(Manager *manager) | RTC::DataFlowComponentBase | |
deactivate(RTC::UniqueId ec_id) | RTC::RTObject_impl | |
default_zmp_offsets | AutoBalancer | private |
deletePort(PortBase &port) | RTC::RTObject_impl | |
deletePort(PortService_ptr port) | RTC::RTObject_impl | |
deletePort(CorbaPort &port) | RTC::RTObject_impl | |
deletePortByName(const char *port_name) | RTC::RTObject_impl | |
detach_context(UniqueId exec_handle) | RTC::RTObject_impl | |
distributeReferenceZMPToWrenches(const hrp::Vector3 &_ref_zmp) | AutoBalancer | |
ECActionListener typedef | RTC::RTObject_impl | |
ECActionListenerType typedef | RTC::RTObject_impl | |
ee_vec | AutoBalancer | private |
emergencyStop() | AutoBalancer | |
exit() | RTC::RTObject_impl | virtual |
fik | AutoBalancer | private |
fikPtr typedef | AutoBalancer | private |
finalize() | RTC::RTObject_impl | virtual |
finalizeContexts() | RTC::RTObject_impl | |
finalizePorts() | RTC::RTObject_impl | |
fix_leg_coords | AutoBalancer | private |
fix_leg_coords2 | AutoBalancer | private |
fixLegToCoords(const hrp::Vector3 &fix_pos, const hrp::Matrix33 &fix_rot) | AutoBalancer | private |
fixLegToCoords2(rats::coordinates &tmp_fix_coords) | AutoBalancer | private |
gait_type | AutoBalancer | private |
GALLOP enum value | AutoBalancer | private |
get_component_profile() | RTC::RTObject_impl | virtual |
get_configuration() | RTC::RTObject_impl | virtual |
get_context(UniqueId exec_handle) | RTC::RTObject_impl | virtual |
get_context_handle(ExecutionContext_ptr cxt) | RTC::RTObject_impl | virtual |
get_device_profile() | RTC::RTObject_impl | virtual |
get_monitoring() | RTC::RTObject_impl | virtual |
get_organizations() | RTC::RTObject_impl | virtual |
get_owned_contexts() | RTC::RTObject_impl | virtual |
get_owned_organizations() | RTC::RTObject_impl | virtual |
get_participating_contexts() | RTC::RTObject_impl | virtual |
get_ports() | RTC::RTObject_impl | virtual |
get_sdo_id() | RTC::RTObject_impl | virtual |
get_sdo_service(const char *id) | RTC::RTObject_impl | virtual |
get_sdo_type() | RTC::RTObject_impl | virtual |
get_service_profile(const char *id) | RTC::RTObject_impl | virtual |
get_service_profiles() | RTC::RTObject_impl | virtual |
get_status(const char *name) | RTC::RTObject_impl | virtual |
get_status_list() | RTC::RTObject_impl | virtual |
getAutoBalancerParam(OpenHRP::AutoBalancerService::AutoBalancerParam &i_param) | AutoBalancer | |
getCategory() | RTC::RTObject_impl | |
getDescription() | RTC::RTObject_impl | |
getExecutionContext(RTC::UniqueId ec_id) | RTC::RTObject_impl | |
getExecutionRate(RTC::UniqueId ec_id) | RTC::RTObject_impl | |
getFootstepParam(OpenHRP::AutoBalancerService::FootstepParam &i_param) | AutoBalancer | |
getGaitGeneratorParam(OpenHRP::AutoBalancerService::GaitGeneratorParam &i_param) | AutoBalancer | |
getGoPosFootstepsSequence(const double &x, const double &y, const double &th, OpenHRP::AutoBalancerService::FootstepsSequence_out o_footstep) | AutoBalancer | |
getInstanceName() | RTC::RTObject_impl | |
getNamingNames() | RTC::RTObject_impl | |
getObjRef() const | RTC::RTObject_impl | |
getOutputParametersForABC() | AutoBalancer | private |
getOutputParametersForIDLE() | AutoBalancer | private |
getOutputParametersForWalking() | AutoBalancer | private |
getProperties() | RTC::RTObject_impl | |
getRemainingFootstepSequence(OpenHRP::AutoBalancerService::FootstepSequence_out o_footstep, CORBA::Long &o_current_fs_idx) | AutoBalancer | |
getTargetParameters() | AutoBalancer | private |
getTypeName() | RTC::RTObject_impl | |
getUseForceModeString() | AutoBalancer | private |
getVendor() | RTC::RTObject_impl | |
getVersion() | RTC::RTObject_impl | |
gg | AutoBalancer | private |
gg_is_walking | AutoBalancer | private |
gg_solved | AutoBalancer | private |
ggPtr typedef | AutoBalancer | private |
goPos(const double &x, const double &y, const double &th) | AutoBalancer | |
goStop() | AutoBalancer | |
goVelocity(const double &vx, const double &vy, const double &vth) | AutoBalancer | |
graspless_manip_arm | AutoBalancer | private |
graspless_manip_mode | AutoBalancer | private |
graspless_manip_p_gain | AutoBalancer | private |
graspless_manip_reference_trans_coords | AutoBalancer | private |
hand_fix_initial_offset | AutoBalancer | private |
idsb | AutoBalancer | private |
ikp | AutoBalancer | private |
init() | RTC::DataFlowComponentBase | |
initialize() | RTC::RTObject_impl | virtual |
input_basePos | AutoBalancer | private |
input_baseRot | AutoBalancer | private |
input_zmp | AutoBalancer | private |
interpolateLegNamesAndZMPOffsets() | AutoBalancer | private |
invdyn_zmp_filters | AutoBalancer | private |
is_alive(ExecutionContext_ptr exec_context) | RTC::RTObject_impl | virtual |
is_hand_fix_initial | AutoBalancer | private |
is_hand_fix_mode | AutoBalancer | private |
is_legged_robot | AutoBalancer | private |
is_stop_mode | AutoBalancer | private |
isOptionalDataContact(const std::string &ee_name) | AutoBalancer | inlineprivate |
isOwnExecutionContext(RTC::UniqueId ec_id) | RTC::RTObject_impl | |
leg_names | AutoBalancer | private |
leg_names_interpolator | AutoBalancer | private |
leg_names_interpolator_ratio | AutoBalancer | private |
limb_stretch_avoidance_time_const | AutoBalancer | private |
limb_stretch_avoidance_vlimit | AutoBalancer | private |
loop | AutoBalancer | private |
m_accRef | AutoBalancer | protected |
m_accRefOut | AutoBalancer | protected |
m_actContactStates | AutoBalancer | protected |
m_actContactStatesIn | AutoBalancer | protected |
m_actionListeners | RTC::RTObject_impl | protected |
m_AutoBalancerServicePort | AutoBalancer | protected |
m_basePos | AutoBalancer | protected |
m_basePose | AutoBalancer | protected |
m_basePoseOut | AutoBalancer | protected |
m_basePosIn | AutoBalancer | protected |
m_basePosOut | AutoBalancer | protected |
m_baseRpy | AutoBalancer | protected |
m_baseRpyIn | AutoBalancer | protected |
m_baseRpyOut | AutoBalancer | protected |
m_baseTform | AutoBalancer | protected |
m_baseTformOut | AutoBalancer | protected |
m_cog | AutoBalancer | protected |
m_cogOut | AutoBalancer | protected |
m_configsets | RTC::RTObject_impl | protected |
m_contactStates | AutoBalancer | protected |
m_contactStatesOut | AutoBalancer | protected |
m_controlSwingSupportTime | AutoBalancer | protected |
m_controlSwingSupportTimeOut | AutoBalancer | protected |
m_created | RTC::RTObject_impl | protected |
m_debugLevel | AutoBalancer | private |
m_diffCP | AutoBalancer | protected |
m_diffCPIn | AutoBalancer | protected |
m_dt | AutoBalancer | private |
m_eclist | RTC::RTObject_impl | protected |
m_ecMine | RTC::RTObject_impl | protected |
m_ecOther | RTC::RTObject_impl | protected |
m_emergencySignal | AutoBalancer | protected |
m_emergencySignalIn | AutoBalancer | protected |
m_exiting | RTC::RTObject_impl | protected |
m_force | AutoBalancer | protected |
m_inports | RTC::RTObject_impl | protected |
m_limbCOPOffset | AutoBalancer | protected |
m_limbCOPOffsetOut | AutoBalancer | protected |
m_mutex | AutoBalancer | private |
m_objref | RTC::RTObject_impl | protected |
m_optionalData | AutoBalancer | protected |
m_optionalDataIn | AutoBalancer | protected |
m_outports | RTC::RTObject_impl | protected |
m_pManager | RTC::RTObject_impl | protected |
m_pORB | RTC::RTObject_impl | protected |
m_portAdmin | RTC::RTObject_impl | protected |
m_portconnListeners | RTC::RTObject_impl | protected |
m_pPOA | RTC::RTObject_impl | protected |
m_profile | RTC::RTObject_impl | protected |
m_properties | RTC::RTObject_impl | protected |
m_pSdoConfig | RTC::RTObject_impl | protected |
m_pSdoConfigImpl | RTC::RTObject_impl | protected |
m_qOut | AutoBalancer | protected |
m_qRef | AutoBalancer | protected |
m_qRefIn | AutoBalancer | protected |
m_readAll | RTC::RTObject_impl | protected |
m_readAllCompletion | RTC::RTObject_impl | protected |
m_ref_force | AutoBalancer | protected |
m_ref_forceIn | AutoBalancer | protected |
m_ref_forceOut | AutoBalancer | protected |
m_refFootOriginExtMoment | AutoBalancer | protected |
m_refFootOriginExtMomentIn | AutoBalancer | protected |
m_refFootOriginExtMomentIsHoldValue | AutoBalancer | protected |
m_refFootOriginExtMomentIsHoldValueIn | AutoBalancer | protected |
m_robot | AutoBalancer | private |
m_sbpCogOffset | AutoBalancer | protected |
m_sbpCogOffsetOut | AutoBalancer | protected |
m_sdoOrganizations | RTC::RTObject_impl | protected |
m_sdoOwnedOrganizations | RTC::RTObject_impl | protected |
m_sdoservice | RTC::RTObject_impl | protected |
m_sdoStatus | RTC::RTObject_impl | protected |
m_service0 | AutoBalancer | protected |
m_toeheelRatio | AutoBalancer | protected |
m_toeheelRatioOut | AutoBalancer | protected |
m_vfs | AutoBalancer | private |
m_walkingStates | AutoBalancer | protected |
m_walkingStatesOut | AutoBalancer | protected |
m_writeAll | RTC::RTObject_impl | protected |
m_writeAllCompletion | RTC::RTObject_impl | protected |
m_zmp | AutoBalancer | protected |
m_zmpIn | AutoBalancer | protected |
m_zmpOut | AutoBalancer | protected |
MODE_ABC enum value | AutoBalancer | private |
MODE_IDLE enum value | AutoBalancer | private |
MODE_NO_FORCE enum value | AutoBalancer | private |
MODE_REF_FORCE enum value | AutoBalancer | private |
MODE_REF_FORCE_RFU_EXT_MOMENT enum value | AutoBalancer | private |
MODE_REF_FORCE_WITH_FOOT enum value | AutoBalancer | private |
MODE_SYNC_TO_ABC enum value | AutoBalancer | private |
MODE_SYNC_TO_IDLE enum value | AutoBalancer | private |
on_aborting(UniqueId exec_handle) | RTC::RTObject_impl | virtual |
on_activated(UniqueId exec_handle) | RTC::RTObject_impl | virtual |
on_deactivated(UniqueId exec_handle) | RTC::RTObject_impl | virtual |
on_error(UniqueId exec_handle) | RTC::RTObject_impl | virtual |
on_execute(UniqueId exec_handle) | RTC::RTObject_impl | virtual |
on_finalize() | RTC::RTObject_impl | virtual |
on_initialize() | RTC::RTObject_impl | virtual |
on_rate_changed(UniqueId exec_handle) | RTC::RTObject_impl | virtual |
on_reset(UniqueId exec_handle) | RTC::RTObject_impl | virtual |
on_shutdown(UniqueId exec_handle) | RTC::RTObject_impl | virtual |
on_startup(UniqueId exec_handle) | RTC::RTObject_impl | virtual |
on_state_update(UniqueId exec_handle) | RTC::RTObject_impl | virtual |
onAborting(RTC::UniqueId exec_handle) | RTC::RTObject_impl | protectedvirtual |
onActivated(RTC::UniqueId ec_id) | AutoBalancer | virtual |
onAddPort(const PortProfile &pprof) | RTC::RTObject_impl | protected |
onAttachExecutionContext(UniqueId ec_id) | RTC::RTObject_impl | protected |
onDeactivated(RTC::UniqueId ec_id) | AutoBalancer | virtual |
onDetachExecutionContext(UniqueId ec_id) | RTC::RTObject_impl | protected |
onError(RTC::UniqueId exec_handle) | RTC::RTObject_impl | protectedvirtual |
onExecute(RTC::UniqueId ec_id) | AutoBalancer | virtual |
onFinalize() | AutoBalancer | virtual |
onInitialize() | AutoBalancer | virtual |
onRateChanged(RTC::UniqueId exec_handle) | RTC::RTObject_impl | protectedvirtual |
onRemovePort(const PortProfile &pprof) | RTC::RTObject_impl | protected |
onReset(RTC::UniqueId exec_handle) | RTC::RTObject_impl | protectedvirtual |
onShutdown(RTC::UniqueId exec_handle) | RTC::RTObject_impl | protectedvirtual |
onStartup(RTC::UniqueId exec_handle) | RTC::RTObject_impl | protectedvirtual |
onStateUpdate(RTC::UniqueId exec_handle) | RTC::RTObject_impl | protectedvirtual |
OrientRotationMatrix(const hrp::Matrix33 &rot, const hrp::Vector3 &axis1, const hrp::Vector3 &axis2) | AutoBalancer | private |
PACE enum value | AutoBalancer | private |
PostCompActionListener typedef | RTC::RTObject_impl | |
PostCompActionListenerType typedef | RTC::RTObject_impl | |
postOnAborting(UniqueId ec_id, ReturnCode_t ret) | RTC::RTObject_impl | protected |
postOnActivated(UniqueId ec_id, ReturnCode_t ret) | RTC::RTObject_impl | protected |
postOnDeactivated(UniqueId ec_id, ReturnCode_t ret) | RTC::RTObject_impl | protected |
postOnError(UniqueId ec_id, ReturnCode_t ret) | RTC::RTObject_impl | protected |
postOnExecute(UniqueId ec_id, ReturnCode_t ret) | RTC::RTObject_impl | protected |
postOnFinalize(UniqueId ec_id, ReturnCode_t ret) | RTC::RTObject_impl | protected |
postOnInitialize(UniqueId ec_id, ReturnCode_t ret) | RTC::RTObject_impl | protected |
postOnRateChanged(UniqueId ec_id, ReturnCode_t ret) | RTC::RTObject_impl | protected |
postOnReset(UniqueId ec_id, ReturnCode_t ret) | RTC::RTObject_impl | protected |
postOnShutdown(UniqueId ec_id, ReturnCode_t ret) | RTC::RTObject_impl | protected |
postOnStartup(UniqueId ec_id, ReturnCode_t ret) | RTC::RTObject_impl | protected |
postOnStateUpdate(UniqueId ec_id, ReturnCode_t ret) | RTC::RTObject_impl | protected |
PreCompActionListener typedef | RTC::RTObject_impl | |
PreCompActionListenerType typedef | RTC::RTObject_impl | |
preOnAborting(UniqueId ec_id) | RTC::RTObject_impl | protected |
preOnActivated(UniqueId ec_id) | RTC::RTObject_impl | protected |
preOnDeactivated(UniqueId ec_id) | RTC::RTObject_impl | protected |
preOnError(UniqueId ec_id) | RTC::RTObject_impl | protected |
preOnExecute(UniqueId ec_id) | RTC::RTObject_impl | protected |
preOnFinalize(UniqueId ec_id) | RTC::RTObject_impl | protected |
preOnInitialize(UniqueId ec_id) | RTC::RTObject_impl | protected |
preOnRateChanged(UniqueId ec_id) | RTC::RTObject_impl | protected |
preOnReset(UniqueId ec_id) | RTC::RTObject_impl | protected |
preOnShutdown(UniqueId ec_id) | RTC::RTObject_impl | protected |
preOnStartup(UniqueId ec_id) | RTC::RTObject_impl | protected |
preOnStateUpdate(UniqueId ec_id) | RTC::RTObject_impl | protected |
prev_imu_sensor_pos | AutoBalancer | private |
prev_imu_sensor_vel | AutoBalancer | private |
prev_ref_zmp | AutoBalancer | private |
readAll() | RTC::RTObject_impl | |
ref_cog | AutoBalancer | private |
ref_forces | AutoBalancer | private |
ref_moments | AutoBalancer | private |
ref_zmp | AutoBalancer | private |
registerInPort(const char *name, InPortBase &inport) | RTC::RTObject_impl | |
registerOutPort(const char *name, OutPortBase &outport) | RTC::RTObject_impl | |
registerPort(PortBase &port) | RTC::RTObject_impl | |
registerPort(PortService_ptr port) | RTC::RTObject_impl | |
registerPort(CorbaPort &port) | RTC::RTObject_impl | |
releaseEmergencyStop() | AutoBalancer | |
removeConfigurationParamListener(ConfigurationParamListenerType type, ConfigurationParamListener *listener) | RTC::RTObject_impl | |
removeConfigurationSetListener(ConfigurationSetListenerType type, ConfigurationSetListener *listener) | RTC::RTObject_impl | |
removeConfigurationSetNameListener(ConfigurationSetNameListenerType type, ConfigurationSetNameListener *listener) | RTC::RTObject_impl | |
removeExecutionContextActionListener(ECActionListenerType listener_type, ECActionListener *listener) | RTC::RTObject_impl | |
removeInPort(InPortBase &port) | RTC::RTObject_impl | |
removeOutPort(OutPortBase &port) | RTC::RTObject_impl | |
removePort(PortBase &port) | RTC::RTObject_impl | |
removePort(PortService_ptr port) | RTC::RTObject_impl | |
removePort(CorbaPort &port) | RTC::RTObject_impl | |
removePortActionListener(PortActionListenerType listener_type, PortActionListener *listener) | RTC::RTObject_impl | |
removePortConnectListener(PortConnectListenerType listener_type, PortConnectListener *listener) | RTC::RTObject_impl | |
removePortConnectRetListener(PortConnectRetListenerType listener_type, PortConnectRetListener *listener) | RTC::RTObject_impl | |
removePostComponentActionListener(PostComponentActionListenerType listener_type, PostComponentActionListener *listener) | RTC::RTObject_impl | |
removePreComponentActionListener(PreComponentActionListenerType listener_type, PreComponentActionListener *listener) | RTC::RTObject_impl | |
removeSdoServiceConsumer(const char *id) | RTC::RTObject_impl | |
removeSdoServiceProvider(const char *id) | RTC::RTObject_impl | |
reset(RTC::UniqueId ec_id) | RTC::RTObject_impl | |
rotateRefForcesForFixCoords(rats::coordinates &tmp_fix_coords) | AutoBalancer | private |
rtclog | RTC::RTObject_impl | protected |
RTObject_impl(Manager *manager) | RTC::RTObject_impl | |
RTObject_impl(CORBA::ORB_ptr orb, PortableServer::POA_ptr poa) | RTC::RTObject_impl | |
sbp_cog_offset | AutoBalancer | private |
sbp_offset | AutoBalancer | private |
sensor_names | AutoBalancer | private |
setAutoBalancerParam(const OpenHRP::AutoBalancerService::AutoBalancerParam &i_param) | AutoBalancer | |
setExecutionRate(RTC::UniqueId ec_id, double rate) | RTC::RTObject_impl | |
setFootSteps(const OpenHRP::AutoBalancerService::FootstepSequence &fs, CORBA::Long overwrite_fs_idx) | AutoBalancer | |
setFootSteps(const OpenHRP::AutoBalancerService::FootstepsSequence &fss, CORBA::Long overwrite_fs_idx) | AutoBalancer | |
setFootStepsWithParam(const OpenHRP::AutoBalancerService::FootstepSequence &fs, const OpenHRP::AutoBalancerService::StepParamSequence &sps, CORBA::Long overwrite_fs_idx) | AutoBalancer | |
setFootStepsWithParam(const OpenHRP::AutoBalancerService::FootstepsSequence &fss, const OpenHRP::AutoBalancerService::StepParamsSequence &spss, CORBA::Long overwrite_fs_idx) | AutoBalancer | |
setGaitGeneratorParam(const OpenHRP::AutoBalancerService::GaitGeneratorParam &i_param) | AutoBalancer | |
setInstanceName(const char *instance_name) | RTC::RTObject_impl | |
setObjRef(const RTObject_ptr rtobj) | RTC::RTObject_impl | |
setProperties(const coil::Properties &prop) | RTC::RTObject_impl | |
setReadAll(bool read=true, bool completion=false) | RTC::RTObject_impl | |
setWriteAll(bool write=true, bool completion=false) | RTC::RTObject_impl | |
shutdown() | RTC::RTObject_impl | protected |
solveFullbodyIK() | AutoBalancer | private |
startABCparam(const ::OpenHRP::AutoBalancerService::StrSequence &limbs) | AutoBalancer | private |
startAutoBalancer(const ::OpenHRP::AutoBalancerService::StrSequence &limbs) | AutoBalancer | |
startWalking() | AutoBalancer | private |
static_balance_point_proc_one(hrp::Vector3 &tmp_input_sbp, const double ref_com_height) | AutoBalancer | private |
stopABCparam() | AutoBalancer | private |
stopAutoBalancer() | AutoBalancer | |
stopWalking() | AutoBalancer | private |
target_root_p | AutoBalancer | private |
target_root_R | AutoBalancer | private |
transition_interpolator | AutoBalancer | private |
transition_interpolator_ratio | AutoBalancer | private |
transition_time | AutoBalancer | private |
TROT enum value | AutoBalancer | private |
updateParameters(const char *config_set) | RTC::RTObject_impl | |
updateTargetCoordsForHandFixMode(rats::coordinates &tmp_fix_coords) | AutoBalancer | private |
updateWalkingVelocityFromHandError(rats::coordinates &tmp_fix_coords) | AutoBalancer | private |
use_force | AutoBalancer | private |
use_limb_stretch_avoidance | AutoBalancer | private |
waitABCTransition() | AutoBalancer | private |
waitFootSteps() | AutoBalancer | |
waitFootStepsEarly(const double tm) | AutoBalancer | |
writeAll() | RTC::RTObject_impl | |
zmp_offset_interpolator | AutoBalancer | private |
zmp_transition_time | AutoBalancer | private |
~AutoBalancer() | AutoBalancer | virtual |
~DataFlowComponentBase(void) | RTC::DataFlowComponentBase | virtual |
~RTObject_impl(void) | RTC::RTObject_impl | virtual |