, including all inherited members.
accels | BodyRTC | [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 | |
addJointGroup(const char *gname, const std::vector< int >jids) | BodyRTC | [inline] |
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 | |
addSensor(Sensor *sensor, int sensorType, int id) | hrp::Body | |
angles | BodyRTC | [private] |
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 | |
Body() | hrp::Body | |
Body(const Body &org) | hrp::Body | |
bodyInterface() | hrp::Body | [static] |
BodyRTC(RTC::Manager *manager=&RTC::Manager::instance()) | BodyRTC | |
bodyrtc_spec | BodyRTC | [private, static] |
calcAngularMomentumJacobian(Link *base, dmatrix &H) | hrp::Body | |
calcCM() | hrp::Body | |
calcCMJacobian(Link *base, dmatrix &J) | hrp::Body | |
calcForwardKinematics(bool calcVelocity=false, bool calcAcceleration=false) | hrp::Body | |
calcInverseDynamics(Link *link, Vector3 &out_f, Vector3 &out_tau) | hrp::Body | |
calcMassMatrix(dmatrix &out_M) | hrp::Body | |
calcTotalMass() | hrp::Body | |
calcTotalMomentum(Vector3 &out_P, Vector3 &out_L) | hrp::Body | |
calcTotalMomentumFromJacobian(Vector3 &out_P, Vector3 &out_L) | hrp::Body | |
calib_status | BodyRTC | [private] |
checkEmergency(emg_reason &o_reason, int &o_id) | BodyRTC | |
clearExternalForces() | hrp::Body | |
clearSensorValues() | hrp::Body | |
commands | BodyRTC | [private] |
createInPort(const std::string &config) | BodyRTC | |
createLight(Link *link, int lightType, const std::string &name) | hrp::Body | |
createOutPort(const std::string &config) | BodyRTC | |
createSensor(Link *link, int sensorType, int id, const std::string &name) | hrp::Body | |
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 | |
dummy | BodyRTC | [private] |
ECActionListener typedef | RTC::RTObject_impl | |
ECActionListenerType typedef | RTC::RTObject_impl | |
EJ_XY | hrp::Body | |
EJ_XYZ | hrp::Body | |
EJ_Z | hrp::Body | |
EMG_FZ enum value | BodyRTC | |
EMG_NONE enum value | BodyRTC | |
emg_reason enum name | BodyRTC | |
EMG_SERVO_ERROR enum value | BodyRTC | |
exit() | RTC::RTObject_impl | [virtual] |
extraJoints | hrp::Body | |
ExtraJointType enum name | hrp::Body | |
finalize() | RTC::RTObject_impl | [virtual] |
finalizeContexts() | RTC::RTObject_impl | |
finalizePorts() | RTC::RTObject_impl | |
forces | BodyRTC | [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] |
getCategory() | RTC::RTObject_impl | |
getDefaultRootPosition(Vector3 &out_p, Matrix33 &out_R) | hrp::Body | |
getDescription() | RTC::RTObject_impl | |
getExecutionContext(RTC::UniqueId ec_id) | RTC::RTObject_impl | |
getExecutionRate(RTC::UniqueId ec_id) | RTC::RTObject_impl | |
getInstanceName() | RTC::RTObject_impl | |
getJointGroup(const char *gname) | BodyRTC | [inline] |
getJointPath(Link *baseLink, Link *targetLink) | hrp::Body | |
getNamingNames() | RTC::RTObject_impl | |
getObjRef() const | RTC::RTObject_impl | |
getProperties() | RTC::RTObject_impl | |
getStatus(OpenHRP::RobotHardwareService::RobotState *rs) | BodyRTC | |
getStatus2(OpenHRP::RobotHardwareService::RobotState2 *rs) | BodyRTC | |
getTypeName() | RTC::RTObject_impl | |
getVendor() | RTC::RTObject_impl | |
getVersion() | RTC::RTObject_impl | |
gyros | BodyRTC | [private] |
init() | RTC::DataFlowComponentBase | |
initialize() | RTC::RTObject_impl | [virtual] |
initializeConfiguration() | hrp::Body | |
installCustomizer() | hrp::Body | |
installCustomizer(BodyCustomizerInterface *customizerInterface) | hrp::Body | |
is_alive(ExecutionContext_ptr exec_context) | RTC::RTObject_impl | [virtual] |
isOwnExecutionContext(RTC::UniqueId ec_id) | RTC::RTObject_impl | |
isStaticModel() | hrp::Body | |
joint(int id) const | hrp::Body | |
joints() const | hrp::Body | |
lengthDigitalInput() | BodyRTC | |
lengthDigitalOutput() | BodyRTC | |
light(const std::string &name) | hrp::Body | |
link(int index) const | hrp::Body | |
link(const std::string &name) const | hrp::Body | |
links() const | hrp::Body | |
linkTraverse() const | hrp::Body | |
m_actionListeners | RTC::RTObject_impl | [protected] |
m_configsets | RTC::RTObject_impl | [protected] |
m_created | RTC::RTObject_impl | [protected] |
m_eclist | RTC::RTObject_impl | [protected] |
m_ecMine | RTC::RTObject_impl | [protected] |
m_ecOther | RTC::RTObject_impl | [protected] |
m_emergencyId | BodyRTC | |
m_emergencyReason | BodyRTC | |
m_exiting | RTC::RTObject_impl | [protected] |
m_inports | BodyRTC | [private] |
m_jointGroups | BodyRTC | [private] |
m_lastServoOn_p | BodyRTC | [private] |
m_lastServoOn_R | BodyRTC | [private] |
m_objref | RTC::RTObject_impl | [protected] |
m_outports | BodyRTC | [private] |
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_readAll | RTC::RTObject_impl | [protected] |
m_readAllCompletion | RTC::RTObject_impl | [protected] |
m_resetPosition | BodyRTC | [private] |
m_RobotHardwareServicePort | BodyRTC | [private] |
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 | BodyRTC | [private] |
m_servoErrorLimit | BodyRTC | |
m_writeAll | RTC::RTObject_impl | [protected] |
m_writeAllCompletion | RTC::RTObject_impl | [protected] |
modelName() | hrp::Body | |
moduleInit(RTC::Manager *) | BodyRTC | [static] |
name() | hrp::Body | |
names2ids(const std::vector< std::string > &i_names, std::vector< int > &o_ids) | BodyRTC | |
numJoints() const | hrp::Body | |
numLinks() const | hrp::Body | |
numSensors(int sensorType) const | hrp::Body | |
numSensorTypes() const | hrp::Body | |
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 | [protected, virtual] |
onActivated(RTC::UniqueId ec_id) | BodyRTC | [inline, virtual] |
onAddPort(const PortProfile &pprof) | RTC::RTObject_impl | [protected] |
onAttachExecutionContext(UniqueId ec_id) | RTC::RTObject_impl | [protected] |
onDeactivated(RTC::UniqueId ec_id) | BodyRTC | [inline, virtual] |
onDetachExecutionContext(UniqueId ec_id) | RTC::RTObject_impl | [protected] |
onError(RTC::UniqueId exec_handle) | RTC::RTObject_impl | [protected, virtual] |
onExecute(RTC::UniqueId exec_handle) | RTC::RTObject_impl | [protected, virtual] |
onFinalize() | RTC::RTObject_impl | [protected, virtual] |
onInitialize() | RTC::RTObject_impl | [protected, virtual] |
onRateChanged(RTC::UniqueId exec_handle) | RTC::RTObject_impl | [protected, virtual] |
onRemovePort(const PortProfile &pprof) | RTC::RTObject_impl | [protected] |
onReset(RTC::UniqueId exec_handle) | RTC::RTObject_impl | [protected, virtual] |
onShutdown(RTC::UniqueId exec_handle) | RTC::RTObject_impl | [protected, virtual] |
onStartup(RTC::UniqueId exec_handle) | RTC::RTObject_impl | [protected, virtual] |
onStateUpdate(RTC::UniqueId exec_handle) | RTC::RTObject_impl | [protected, virtual] |
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] |
postOneStep() | BodyRTC | |
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] |
power(int jid, bool turnon) | BodyRTC | [inline] |
power(const char *jname, bool turnon) | BodyRTC | |
power_status | BodyRTC | [private] |
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] |
preOneStep() | BodyRTC | |
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] |
putInformation(std::ostream &out) | hrp::Body | |
readAll() | RTC::RTObject_impl | |
readCalibState(const int i) | BodyRTC | [inline] |
readDataPorts() | BodyRTC | |
readDigitalInput(char *o_din) | BodyRTC | |
readDigitalOutput(char *o_dout) | BodyRTC | |
readPowerState(const int i) | BodyRTC | [inline] |
readServoState(const int i) | BodyRTC | [inline] |
refCounter() | hrp::Referenced | [protected] |
Referenced() | hrp::Referenced | |
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 | |
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 | |
resetPosition() | BodyRTC | [inline] |
rootLink() const | hrp::Body | |
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 | |
sensor(int sensorType, int sensorId) const | hrp::Body | |
sensor(int id) const | hrp::Body | |
sensor(const std::string &name) const | hrp::Body | |
servo(const char *jname, bool turnon) | BodyRTC | |
servo(int jid, bool turnon) | BodyRTC | [inline] |
servo_status | BodyRTC | [private] |
setColumnOfMassMatrix(dmatrix &M, int column) | hrp::Body | |
setDefaultRootPosition(const Vector3 &p, const Matrix33 &R) | hrp::Body | |
setExecutionRate(RTC::UniqueId ec_id, double rate) | RTC::RTObject_impl | |
setInstanceName(const char *instance_name) | RTC::RTObject_impl | |
setModelName(const std::string &name) | hrp::Body | |
setName(const std::string &name) | hrp::Body | |
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 | |
setRootLink(Link *link) | hrp::Body | |
setServoErrorLimit(const char *i_jname, double i_limit) | BodyRTC | |
setup() | BodyRTC | |
setVirtualJointForces() | hrp::Body | |
setWriteAll(bool write=true, bool completion=false) | RTC::RTObject_impl | |
shutdown() | RTC::RTObject_impl | [protected] |
totalMass() const | hrp::Body | |
updateLinkColdetModelPositions() | hrp::Body | |
updateLinkTree() | hrp::Body | |
updateParameters(const char *config_set) | RTC::RTObject_impl | |
writeAll() | RTC::RTObject_impl | |
writeDataPorts(double time) | BodyRTC | |
writeDigitalOutput(const char *i_dout) | BodyRTC | |
writeDigitalOutputWithMask(const char *i_dout, const char *i_mask) | BodyRTC | |
~Body() | hrp::Body | [virtual] |
~BodyRTC(void) | BodyRTC | [virtual] |
~DataFlowComponentBase(void) | RTC::DataFlowComponentBase | [virtual] |
~Referenced() | hrp::Referenced | [virtual] |
~RTObject_impl(void) | RTC::RTObject_impl | [virtual] |