act_base_rpy | Stabilizer | private |
act_cog | Stabilizer | private |
act_cogvel | Stabilizer | private |
act_cogvel_filter | Stabilizer | private |
act_contact_states | Stabilizer | private |
act_cp | Stabilizer | private |
act_ee_p | Stabilizer | private |
act_ee_R | Stabilizer | private |
act_force | Stabilizer | private |
act_total_foot_origin_moment | Stabilizer | private |
act_zmp | Stabilizer | private |
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 | |
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 | |
attach_context(ExecutionContext_ptr exec_context) | RTC::RTObject_impl | |
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 | |
calcContactMatrix(hrp::dmatrix &tm, const std::vector< hrp::Vector3 > &contact_p) | Stabilizer | |
calcDampingControl(const double tau_d, const double tau, const double prev_d, const double DD, const double TT) | Stabilizer | |
calcDampingControl(const hrp::Vector3 &prev_d, const hrp::Vector3 &TT) | Stabilizer | |
calcDampingControl(const double prev_d, const double TT) | Stabilizer | |
calcDampingControl(const hrp::Vector3 &tau_d, const hrp::Vector3 &tau, const hrp::Vector3 &prev_d, const hrp::Vector3 &DD, const hrp::Vector3 &TT) | Stabilizer | |
calcDiffFootOriginExtMoment() | Stabilizer | |
calcEEForceMomentControl() | Stabilizer | |
calcFootOriginCoords(hrp::Vector3 &foot_origin_pos, hrp::Matrix33 &foot_origin_rot) | Stabilizer | |
calcMaxTransitionCount() | Stabilizer | inline |
calcRUNST() | Stabilizer | |
calcStateForEmergencySignal() | Stabilizer | |
calcSwingEEModification() | Stabilizer | |
calcSwingSupportLimbGain() | Stabilizer | |
calcTorque() | Stabilizer | |
calcTPCC() | Stabilizer | |
calcZMP(hrp::Vector3 &ret_zmp, const double zmp_z) | Stabilizer | |
cmode enum name | Stabilizer | private |
contact_decision_threshold | Stabilizer | private |
contact_states_index_map | Stabilizer | private |
control_mode | Stabilizer | private |
cop_check_margin | Stabilizer | private |
cp_check_margin | Stabilizer | private |
cp_offset | Stabilizer | private |
current_base_pos | Stabilizer | private |
current_base_rpy | Stabilizer | private |
current_root_p | Stabilizer | private |
current_root_R | Stabilizer | private |
d_pos_z_root | Stabilizer | private |
d_rpy | Stabilizer | private |
d_run_b | Stabilizer | private |
DataFlowComponentBase(Manager *manager) | RTC::DataFlowComponentBase | |
deactivate(RTC::UniqueId ec_id) | RTC::RTObject_impl | |
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 | |
detection_count_to_air | Stabilizer | private |
diff_cp | Stabilizer | private |
diff_foot_origin_ext_moment | Stabilizer | private |
dt | Stabilizer | private |
ECActionListener typedef | RTC::RTObject_impl | |
ECActionListenerType typedef | RTC::RTObject_impl | |
eefm_body_attitude_control_gain | Stabilizer | private |
eefm_body_attitude_control_time_const | Stabilizer | private |
eefm_gravitational_acceleration | Stabilizer | private |
eefm_k1 | Stabilizer | private |
eefm_k2 | Stabilizer | private |
eefm_k3 | Stabilizer | private |
eefm_pos_margin_time | Stabilizer | private |
eefm_pos_time_const_swing | Stabilizer | private |
eefm_pos_transition_time | Stabilizer | private |
eefm_swing_damping_force_thre | Stabilizer | private |
eefm_swing_damping_moment_thre | Stabilizer | private |
eefm_swing_pos_damping_gain | Stabilizer | private |
eefm_swing_rot_damping_gain | Stabilizer | private |
eefm_use_force_difference_control | Stabilizer | private |
eefm_use_swing_damping | Stabilizer | private |
eefm_zmp_delay_time_const | Stabilizer | private |
emergency_check_mode | Stabilizer | private |
exit() | RTC::RTObject_impl | virtual |
finalize() | RTC::RTObject_impl | virtual |
finalizeContexts() | RTC::RTObject_impl | |
finalizePorts() | RTC::RTObject_impl | |
fixLegToCoords(const std::string &leg, const rats::coordinates &coords) | Stabilizer | |
foot_origin_offset | Stabilizer | 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 |
getActualParameters() | Stabilizer | |
getCategory() | RTC::RTObject_impl | |
getCurrentParameters() | Stabilizer | |
getDescription() | RTC::RTObject_impl | |
getExecutionContext(RTC::UniqueId ec_id) | RTC::RTObject_impl | |
getExecutionRate(RTC::UniqueId ec_id) | RTC::RTObject_impl | |
getFootmidCoords(rats::coordinates &ret) | Stabilizer | |
getInstanceName() | RTC::RTObject_impl | |
getNamingNames() | RTC::RTObject_impl | |
getObjRef() const | RTC::RTObject_impl | |
getParameter(OpenHRP::StabilizerService::stParam &i_stp) | Stabilizer | |
getProperties() | RTC::RTObject_impl | |
getStabilizerAlgorithmString(OpenHRP::StabilizerService::STAlgorithm _st_algorithm) | Stabilizer | |
getTargetParameters() | Stabilizer | |
getTypeName() | RTC::RTObject_impl | |
getVendor() | RTC::RTObject_impl | |
getVersion() | RTC::RTObject_impl | |
init() | RTC::DataFlowComponentBase | |
initial_cp_too_large_error | Stabilizer | private |
initialize() | RTC::RTObject_impl | virtual |
is_air_counter | Stabilizer | private |
is_alive(ExecutionContext_ptr exec_context) | RTC::RTObject_impl | virtual |
is_emergency | Stabilizer | private |
is_estop_while_walking | Stabilizer | private |
is_feedback_control_enable | Stabilizer | private |
is_ik_enable | Stabilizer | private |
is_legged_robot | Stabilizer | private |
is_seq_interpolating | Stabilizer | private |
is_walking | Stabilizer | private |
is_zmp_calc_enable | Stabilizer | private |
isContact(const size_t idx) | Stabilizer | inline |
isOwnExecutionContext(RTC::UniqueId ec_id) | RTC::RTObject_impl | |
jpe_v | Stabilizer | private |
k_brot_p | Stabilizer | private |
k_brot_tc | Stabilizer | private |
k_run_b | Stabilizer | private |
k_tpcc_p | Stabilizer | private |
k_tpcc_x | Stabilizer | private |
limb_stretch_avoidance_time_const | Stabilizer | private |
limb_stretch_avoidance_vlimit | Stabilizer | private |
limbStretchAvoidanceControl(const std::vector< hrp::Vector3 > &ee_p, const std::vector< hrp::Matrix33 > &ee_R) | Stabilizer | |
loop | Stabilizer | private |
m_actBaseRpy | Stabilizer | protected |
m_actBaseRpyOut | Stabilizer | protected |
m_actContactStates | Stabilizer | protected |
m_actContactStatesOut | Stabilizer | protected |
m_actCP | Stabilizer | protected |
m_actCPOut | Stabilizer | protected |
m_actionListeners | RTC::RTObject_impl | protected |
m_allEEComp | Stabilizer | protected |
m_allEECompOut | Stabilizer | protected |
m_allRefWrench | Stabilizer | protected |
m_allRefWrenchOut | Stabilizer | protected |
m_basePos | Stabilizer | protected |
m_basePosIn | Stabilizer | protected |
m_baseRpy | Stabilizer | protected |
m_baseRpyIn | Stabilizer | protected |
m_configsets | RTC::RTObject_impl | protected |
m_contactStates | Stabilizer | protected |
m_contactStatesIn | Stabilizer | protected |
m_controlSwingSupportTime | Stabilizer | protected |
m_controlSwingSupportTimeIn | Stabilizer | protected |
m_COPInfo | Stabilizer | protected |
m_COPInfoOut | Stabilizer | protected |
m_created | RTC::RTObject_impl | protected |
m_currentBasePos | Stabilizer | protected |
m_currentBasePosOut | Stabilizer | protected |
m_currentBaseRpy | Stabilizer | protected |
m_currentBaseRpyOut | Stabilizer | protected |
m_debugData | Stabilizer | protected |
m_debugDataOut | Stabilizer | protected |
m_debugLevel | Stabilizer | private |
m_diffCP | Stabilizer | protected |
m_diffCPOut | Stabilizer | protected |
m_diffFootOriginExtMoment | Stabilizer | protected |
m_diffFootOriginExtMomentOut | Stabilizer | protected |
m_eclist | RTC::RTObject_impl | protected |
m_ecMine | RTC::RTObject_impl | protected |
m_ecOther | RTC::RTObject_impl | protected |
m_emergencySignal | Stabilizer | protected |
m_emergencySignalOut | Stabilizer | protected |
m_exiting | RTC::RTObject_impl | protected |
m_f_z | Stabilizer | private |
m_inports | RTC::RTObject_impl | protected |
m_is_falling_counter | Stabilizer | private |
m_limbCOPOffset | Stabilizer | protected |
m_limbCOPOffsetIn | Stabilizer | protected |
m_mutex | Stabilizer | private |
m_objref | RTC::RTObject_impl | protected |
m_originActCog | Stabilizer | protected |
m_originActCogOut | Stabilizer | protected |
m_originActCogVel | Stabilizer | protected |
m_originActCogVelOut | Stabilizer | protected |
m_originActZmp | Stabilizer | protected |
m_originActZmpOut | Stabilizer | protected |
m_originNewZmp | Stabilizer | protected |
m_originNewZmpOut | Stabilizer | protected |
m_originRefCog | Stabilizer | protected |
m_originRefCogOut | Stabilizer | protected |
m_originRefCogVel | Stabilizer | protected |
m_originRefCogVelOut | Stabilizer | protected |
m_originRefZmp | Stabilizer | protected |
m_originRefZmpOut | Stabilizer | 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_qCurrent | Stabilizer | protected |
m_qCurrentIn | Stabilizer | protected |
m_qRef | Stabilizer | protected |
m_qRefIn | Stabilizer | protected |
m_qRefOut | Stabilizer | protected |
m_qRefSeq | Stabilizer | protected |
m_qRefSeqIn | Stabilizer | protected |
m_readAll | RTC::RTObject_impl | protected |
m_readAllCompletion | RTC::RTObject_impl | protected |
m_ref_wrenches | Stabilizer | protected |
m_ref_wrenchesIn | Stabilizer | protected |
m_refCP | Stabilizer | protected |
m_refCPOut | Stabilizer | protected |
m_robot | Stabilizer | private |
m_rpy | Stabilizer | protected |
m_rpyIn | Stabilizer | protected |
m_sbpCogOffset | Stabilizer | protected |
m_sbpCogOffsetIn | Stabilizer | 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 | Stabilizer | protected |
m_StabilizerServicePort | Stabilizer | protected |
m_tau | Stabilizer | protected |
m_tau_x | Stabilizer | private |
m_tau_y | Stabilizer | private |
m_tauOut | Stabilizer | protected |
m_toeheelRatio | Stabilizer | protected |
m_toeheelRatioIn | Stabilizer | protected |
m_torque_d | Stabilizer | private |
m_torque_k | Stabilizer | private |
m_vfs | Stabilizer | private |
m_walkingStates | Stabilizer | protected |
m_walkingStatesIn | Stabilizer | protected |
m_will_fall_counter | Stabilizer | private |
m_wrenches | Stabilizer | protected |
m_wrenchesIn | Stabilizer | protected |
m_writeAll | RTC::RTObject_impl | protected |
m_writeAllCompletion | RTC::RTObject_impl | protected |
m_zmp | Stabilizer | protected |
m_zmpOut | Stabilizer | protected |
m_zmpRef | Stabilizer | protected |
m_zmpRefIn | Stabilizer | protected |
margined_support_polygon_vetices | Stabilizer | private |
MODE_AIR enum value | Stabilizer | private |
MODE_IDLE enum value | Stabilizer | private |
MODE_ST enum value | Stabilizer | private |
MODE_SYNC_TO_AIR enum value | Stabilizer | private |
MODE_SYNC_TO_IDLE enum value | Stabilizer | private |
moveBasePosRotForBodyRPYControl() | Stabilizer | |
new_refzmp | Stabilizer | 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_ground | Stabilizer | private |
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) | Stabilizer | virtual |
onAddPort(const PortProfile &pprof) | RTC::RTObject_impl | protected |
onAttachExecutionContext(UniqueId ec_id) | RTC::RTObject_impl | protected |
onDeactivated(RTC::UniqueId ec_id) | Stabilizer | virtual |
onDetachExecutionContext(UniqueId ec_id) | RTC::RTObject_impl | protected |
onError(RTC::UniqueId exec_handle) | RTC::RTObject_impl | protectedvirtual |
onExecute(RTC::UniqueId ec_id) | Stabilizer | virtual |
onFinalize() | Stabilizer | virtual |
onInitialize() | Stabilizer | 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 |
pangx | Stabilizer | private |
pangx_ref | Stabilizer | private |
pangy | Stabilizer | private |
pangy_ref | Stabilizer | private |
pdr | Stabilizer | private |
pos_ctrl | Stabilizer | 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_act_cog | Stabilizer | private |
prev_act_foot_origin_rot | Stabilizer | private |
prev_act_force_z | Stabilizer | private |
prev_ref_cog | Stabilizer | private |
prev_ref_contact_states | Stabilizer | private |
prev_ref_foot_origin_rot | Stabilizer | private |
prev_ref_zmp | Stabilizer | private |
projected_normal | Stabilizer | private |
qorg | Stabilizer | private |
qrefv | Stabilizer | private |
rdx | Stabilizer | private |
rdy | Stabilizer | private |
readAll() | RTC::RTObject_impl | |
ref_cog | Stabilizer | private |
ref_cogvel | Stabilizer | private |
ref_contact_states | Stabilizer | private |
ref_cp | Stabilizer | private |
ref_foot_origin_rot | Stabilizer | private |
ref_force | Stabilizer | private |
ref_moment | Stabilizer | private |
ref_total_foot_origin_moment | Stabilizer | private |
ref_total_force | Stabilizer | private |
ref_total_moment | Stabilizer | private |
ref_zmp | Stabilizer | private |
ref_zmp_aux | Stabilizer | 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 | |
rel_act_cp | Stabilizer | private |
rel_act_zmp | Stabilizer | private |
rel_cog | Stabilizer | private |
rel_ee_name | Stabilizer | private |
rel_ee_pos | Stabilizer | private |
rel_ee_rot | Stabilizer | private |
rel_ref_cp | Stabilizer | private |
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 | |
reset_emergency_flag | Stabilizer | private |
root_rot_compensation_limit | Stabilizer | 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 | |
rx | Stabilizer | private |
ry | Stabilizer | private |
sbp_cog_offset | Stabilizer | private |
setBoolSequenceParam(std::vector< bool > &st_bool_values, const OpenHRP::StabilizerService::BoolSequence &output_bool_values, const std::string &prop_name) | Stabilizer | |
setBoolSequenceParamWithCheckContact(std::vector< bool > &st_bool_values, const OpenHRP::StabilizerService::BoolSequence &output_bool_values, const std::string &prop_name) | Stabilizer | |
setExecutionRate(RTC::UniqueId ec_id, double rate) | RTC::RTObject_impl | |
setInstanceName(const char *instance_name) | RTC::RTObject_impl | |
setObjRef(const RTObject_ptr rtobj) | RTC::RTObject_impl | |
setParameter(const OpenHRP::StabilizerService::stParam &i_stp) | Stabilizer | |
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 |
st_algorithm | Stabilizer | private |
Stabilizer(RTC::Manager *manager) | Stabilizer | |
startStabilizer(void) | Stabilizer | |
stikp | Stabilizer | private |
stopStabilizer(void) | Stabilizer | |
support_polygon_vetices | Stabilizer | private |
sync_2_idle() | Stabilizer | |
sync_2_st() | Stabilizer | |
szd | Stabilizer | private |
target_ee_p | Stabilizer | private |
target_ee_R | Stabilizer | private |
target_foot_midcoords | Stabilizer | private |
target_foot_origin_rot | Stabilizer | private |
target_root_p | Stabilizer | private |
target_root_R | Stabilizer | private |
tilt_margin | Stabilizer | private |
toeheel_ratio | Stabilizer | private |
total_mass | Stabilizer | private |
transition_count | Stabilizer | private |
transition_joint_q | Stabilizer | private |
transition_smooth_gain | Stabilizer | private |
transition_time | Stabilizer | private |
updateParameters(const char *config_set) | RTC::RTObject_impl | |
use_limb_stretch_avoidance | Stabilizer | private |
use_zmp_truncation | Stabilizer | private |
vlimit(double value, double llimit_value, double ulimit_value) | Stabilizer | |
vlimit(const hrp::Vector3 &value, double llimit_value, double ulimit_value) | Stabilizer | |
vlimit(const hrp::Vector3 &value, const hrp::Vector3 &limit_value) | Stabilizer | |
vlimit(const hrp::Vector3 &value, const hrp::Vector3 &llimit_value, const hrp::Vector3 &ulimit_value) | Stabilizer | |
waitSTTransition() | Stabilizer | |
writeAll() | RTC::RTObject_impl | |
zmp_origin_off | Stabilizer | private |
~DataFlowComponentBase(void) | RTC::DataFlowComponentBase | virtual |
~RTObject_impl(void) | RTC::RTObject_impl | virtual |
~Stabilizer() | Stabilizer | virtual |