|
int | addJointGroup (const char *gname, const std::vector< int >jids) |
|
| BodyRTC (RTC::Manager *manager=&RTC::Manager::instance()) |
|
bool | checkEmergency (emg_reason &o_reason, int &o_id) |
|
void | createInPort (const std::string &config) |
|
void | createOutPort (const std::string &config) |
|
std::vector< int > | getJointGroup (const char *gname) |
|
void | getStatus (OpenHRP::RobotHardwareService::RobotState *rs) |
|
void | getStatus2 (OpenHRP::RobotHardwareService::RobotState2 *rs) |
|
int | lengthDigitalInput () |
|
int | lengthDigitalOutput () |
|
bool | names2ids (const std::vector< std::string > &i_names, std::vector< int > &o_ids) |
|
RTC::ReturnCode_t | onActivated (RTC::UniqueId ec_id) |
|
RTC::ReturnCode_t | onDeactivated (RTC::UniqueId ec_id) |
|
bool | postOneStep () |
|
bool | power (int jid, bool turnon) |
|
bool | power (const char *jname, bool turnon) |
|
bool | preOneStep () |
|
int | readCalibState (const int i) |
|
void | readDataPorts () |
|
bool | readDigitalInput (char *o_din) |
|
bool | readDigitalOutput (char *o_dout) |
|
int | readPowerState (const int i) |
|
int | readServoState (const int i) |
|
bool | resetPosition () |
|
bool | servo (const char *jname, bool turnon) |
|
bool | servo (int jid, bool turnon) |
|
bool | setServoErrorLimit (const char *i_jname, double i_limit) |
|
RTC::ReturnCode_t | setup () |
|
void | writeDataPorts (double time) |
|
bool | writeDigitalOutput (const char *i_dout) |
|
bool | writeDigitalOutputWithMask (const char *i_dout, const char *i_mask) |
|
virtual | ~BodyRTC (void) |
|
Public Member Functions inherited from hrp::Body |
void | addSensor (Sensor *sensor, int sensorType, int id) |
|
| Body () |
|
| Body (const Body &org) |
|
void | calcAngularMomentumJacobian (Link *base, dmatrix &H) |
|
Vector3 | calcCM () |
|
void | calcCMJacobian (Link *base, dmatrix &J) |
|
void | calcForwardKinematics (bool calcVelocity=false, bool calcAcceleration=false) |
|
void | calcInverseDynamics (Link *link, Vector3 &out_f, Vector3 &out_tau) |
|
void | calcMassMatrix (dmatrix &out_M) |
|
double | calcTotalMass () |
|
void | calcTotalMomentum (Vector3 &out_P, Vector3 &out_L) |
|
void | calcTotalMomentumFromJacobian (Vector3 &out_P, Vector3 &out_L) |
|
void | clearExternalForces () |
|
void | clearSensorValues () |
|
Light * | createLight (Link *link, int lightType, const std::string &name) |
|
Sensor * | createSensor (Link *link, int sensorType, int id, const std::string &name) |
|
void | getDefaultRootPosition (Vector3 &out_p, Matrix33 &out_R) |
|
JointPathPtr | getJointPath (Link *baseLink, Link *targetLink) |
|
void | initializeConfiguration () |
|
bool | installCustomizer () |
|
bool | installCustomizer (BodyCustomizerInterface *customizerInterface) |
|
bool | isStaticModel () |
|
Link * | joint (int id) const |
|
const std::vector< Link * > & | joints () const |
|
Light * | light (const std::string &name) |
|
Link * | link (int index) const |
|
Link * | link (const std::string &name) const |
|
const LinkTraverse & | links () const |
|
const LinkTraverse & | linkTraverse () const |
|
const std::string & | modelName () |
|
const std::string & | name () |
|
unsigned int | numJoints () const |
|
unsigned int | numLinks () const |
|
unsigned int | numSensors (int sensorType) const |
|
unsigned int | numSensorTypes () const |
|
void | putInformation (std::ostream &out) |
|
Link * | rootLink () const |
|
Sensor * | sensor (int sensorType, int sensorId) const |
|
TSensor * | sensor (const std::string &name) const |
|
TSensor * | sensor (int id) const |
|
void | setColumnOfMassMatrix (dmatrix &M, int column) |
|
void | setDefaultRootPosition (const Vector3 &p, const Matrix33 &R) |
|
void | setModelName (const std::string &name) |
|
void | setName (const std::string &name) |
|
void | setRootLink (Link *link) |
|
void | setVirtualJointForces () |
|
double | totalMass () const |
|
void | updateLinkColdetModelPositions () |
|
void | updateLinkTree () |
|
virtual | ~Body () |
|
| Referenced () |
|
virtual | ~Referenced () |
|
| DataFlowComponentBase (Manager *manager) |
|
void | init () |
|
virtual | ~DataFlowComponentBase (void) |
|
ReturnCode_t | activate (RTC::UniqueId ec_id) |
|
void | addConfigurationParamListener (ConfigurationParamListenerType type, ConfigurationParamListener *listener, bool autoclean=true) |
|
ConfigurationParamListener * | addConfigurationParamListener (ConfigurationParamListenerType listener_type, Listener &obj, void(Listener::*memfunc)(const char *, const char *)) |
|
void | addConfigurationSetListener (ConfigurationSetListenerType type, ConfigurationSetListener *listener, bool autoclean=true) |
|
ConfigurationSetListener * | addConfigurationSetListener (ConfigurationSetListenerType listener_type, Listener &obj, void(Listener::*memfunc)(const coil::Properties &config_set)) |
|
void | addConfigurationSetNameListener (ConfigurationSetNameListenerType type, ConfigurationSetNameListener *listener, bool autoclean=true) |
|
ConfigurationSetNameListener * | addConfigurationSetNameListener (ConfigurationSetNameListenerType type, Listener &obj, void(Listener::*memfunc)(const char *)) |
|
void | addExecutionContextActionListener (ECActionListenerType listener_type, ECActionListener *listener, bool autoclean=true) |
|
ECActionListener * | addExecutionContextActionListener (ECActionListenerType listener_type, Listener &obj, void(Listener::*memfunc)(UniqueId)) |
|
bool | addInPort (const char *name, InPortBase &inport) |
|
bool | addOutPort (const char *name, OutPortBase &outport) |
|
bool | addPort (PortBase &port) |
|
bool | addPort (PortService_ptr port) |
|
bool | addPort (CorbaPort &port) |
|
PortActionListener * | addPortActionListener (PortActionListenerType listener_type, Listener &obj, void(Listener::*memfunc)(const RTC::PortProfile &)) |
|
void | addPortActionListener (PortActionListenerType listener_type, PortActionListener *listener, bool autoclean=true) |
|
void | addPortConnectListener (PortConnectListenerType listener_type, PortConnectListener *listener, bool autoclean=true) |
|
PortConnectListener * | addPortConnectListener (PortConnectListenerType listener_type, Listener &obj, void(Listener::*memfunc)(const char *, ConnectorProfile &)) |
|
void | addPortConnectRetListener (PortConnectRetListenerType listener_type, PortConnectRetListener *listener, bool autoclean=true) |
|
PortConnectRetListener * | addPortConnectRetListener (PortConnectRetListenerType listener_type, Listener &obj, void(Listener::*memfunc)(const char *, ConnectorProfile &, ReturnCode_t)) |
|
void | addPostComponentActionListener (PostComponentActionListenerType listener_type, PostComponentActionListener *listener, bool autoclean=true) |
|
PostComponentActionListener * | addPostComponentActionListener (PostCompActionListenerType listener_type, Listener &obj, void(Listener::*memfunc)(UniqueId ec_id, ReturnCode_t ret)) |
|
void | addPreComponentActionListener (PreComponentActionListenerType listener_type, PreComponentActionListener *listener, bool autoclean=true) |
|
PreComponentActionListener * | addPreComponentActionListener (PreCompActionListenerType listener_type, Listener &obj, void(Listener::*memfunc)(UniqueId ec_id)) |
|
bool | addSdoServiceConsumer (const SDOPackage::ServiceProfile &prof) |
|
bool | addSdoServiceProvider (const SDOPackage::ServiceProfile &prof, SdoServiceProviderBase *provider) |
|
UniqueId | attach_context (ExecutionContext_ptr exec_context) |
|
UniqueId | bindContext (ExecutionContext_ptr exec_context) |
|
bool | bindParameter (const char *param_name, VarType &var, const char *def_val, bool(*trans)(VarType &, const char *)=coil::stringTo) |
|
ReturnCode_t | deactivate (RTC::UniqueId ec_id) |
|
void | deletePort (PortService_ptr port) |
|
void | deletePort (CorbaPort &port) |
|
void | deletePort (PortBase &port) |
|
void | deletePortByName (const char *port_name) |
|
ReturnCode_t | detach_context (UniqueId exec_handle) |
|
virtual ReturnCode_t | exit () |
|
virtual ReturnCode_t | finalize () |
|
void | finalizeContexts () |
|
void | finalizePorts () |
|
virtual ComponentProfile * | get_component_profile () |
|
virtual SDOPackage::Configuration_ptr | get_configuration () |
|
virtual ExecutionContext_ptr | get_context (UniqueId exec_handle) |
|
virtual ExecutionContextHandle_t | get_context_handle (ExecutionContext_ptr cxt) |
|
virtual SDOPackage::DeviceProfile * | get_device_profile () |
|
virtual SDOPackage::Monitoring_ptr | get_monitoring () |
|
virtual SDOPackage::OrganizationList * | get_organizations () |
|
virtual ExecutionContextList * | get_owned_contexts () |
|
virtual SDOPackage::OrganizationList * | get_owned_organizations () |
|
virtual ExecutionContextList * | get_participating_contexts () |
|
virtual PortServiceList * | get_ports () |
|
virtual char * | get_sdo_id () |
|
virtual SDOPackage::SDOService_ptr | get_sdo_service (const char *id) |
|
virtual char * | get_sdo_type () |
|
virtual SDOPackage::ServiceProfile * | get_service_profile (const char *id) |
|
virtual SDOPackage::ServiceProfileList * | get_service_profiles () |
|
virtual CORBA::Any * | get_status (const char *name) |
|
virtual SDOPackage::NVList * | get_status_list () |
|
const char * | getCategory () |
|
const char * | getDescription () |
|
ExecutionContext_ptr | getExecutionContext (RTC::UniqueId ec_id) |
|
double | getExecutionRate (RTC::UniqueId ec_id) |
|
const char * | getInstanceName () |
|
std::vector< std::string > | getNamingNames () |
|
RTObject_ptr | getObjRef () const |
|
coil::Properties & | getProperties () |
|
const char * | getTypeName () |
|
const char * | getVendor () |
|
const char * | getVersion () |
|
virtual ReturnCode_t | initialize () |
|
virtual CORBA::Boolean | is_alive (ExecutionContext_ptr exec_context) |
|
bool | isOwnExecutionContext (RTC::UniqueId ec_id) |
|
virtual ReturnCode_t | on_aborting (UniqueId exec_handle) |
|
virtual ReturnCode_t | on_activated (UniqueId exec_handle) |
|
virtual ReturnCode_t | on_deactivated (UniqueId exec_handle) |
|
virtual ReturnCode_t | on_error (UniqueId exec_handle) |
|
virtual ReturnCode_t | on_execute (UniqueId exec_handle) |
|
virtual ReturnCode_t | on_finalize () |
|
virtual ReturnCode_t | on_initialize () |
|
virtual ReturnCode_t | on_rate_changed (UniqueId exec_handle) |
|
virtual ReturnCode_t | on_reset (UniqueId exec_handle) |
|
virtual ReturnCode_t | on_shutdown (UniqueId exec_handle) |
|
virtual ReturnCode_t | on_startup (UniqueId exec_handle) |
|
virtual ReturnCode_t | on_state_update (UniqueId exec_handle) |
|
bool | readAll () |
|
void | registerInPort (const char *name, InPortBase &inport) |
|
void | registerOutPort (const char *name, OutPortBase &outport) |
|
void | registerPort (PortBase &port) |
|
void | registerPort (PortService_ptr port) |
|
void | registerPort (CorbaPort &port) |
|
void | removeConfigurationParamListener (ConfigurationParamListenerType type, ConfigurationParamListener *listener) |
|
void | removeConfigurationSetListener (ConfigurationSetListenerType type, ConfigurationSetListener *listener) |
|
void | removeConfigurationSetNameListener (ConfigurationSetNameListenerType type, ConfigurationSetNameListener *listener) |
|
void | removeExecutionContextActionListener (ECActionListenerType listener_type, ECActionListener *listener) |
|
bool | removeInPort (InPortBase &port) |
|
bool | removeOutPort (OutPortBase &port) |
|
bool | removePort (PortService_ptr port) |
|
bool | removePort (CorbaPort &port) |
|
bool | removePort (PortBase &port) |
|
void | removePortActionListener (PortActionListenerType listener_type, PortActionListener *listener) |
|
void | removePortConnectListener (PortConnectListenerType listener_type, PortConnectListener *listener) |
|
void | removePortConnectRetListener (PortConnectRetListenerType listener_type, PortConnectRetListener *listener) |
|
void | removePostComponentActionListener (PostComponentActionListenerType listener_type, PostComponentActionListener *listener) |
|
void | removePreComponentActionListener (PreComponentActionListenerType listener_type, PreComponentActionListener *listener) |
|
bool | removeSdoServiceConsumer (const char *id) |
|
bool | removeSdoServiceProvider (const char *id) |
|
ReturnCode_t | reset (RTC::UniqueId ec_id) |
|
| RTObject_impl (CORBA::ORB_ptr orb, PortableServer::POA_ptr poa) |
|
| RTObject_impl (Manager *manager) |
|
ReturnCode_t | setExecutionRate (RTC::UniqueId ec_id, double rate) |
|
void | setInstanceName (const char *instance_name) |
|
void | setObjRef (const RTObject_ptr rtobj) |
|
void | setProperties (const coil::Properties &prop) |
|
void | setReadAll (bool read=true, bool completion=false) |
|
void | setWriteAll (bool write=true, bool completion=false) |
|
void | updateParameters (const char *config_set) |
|
bool | writeAll () |
|
virtual | ~RTObject_impl (void) |
|
Definition at line 60 of file BodyRTC.h.