Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Private Attributes | Static Private Attributes | List of all members
BodyRTC Class Reference

#include <BodyRTC.h>

Inheritance diagram for BodyRTC:
Inheritance graph
[legend]

Public Types

enum  emg_reason { EMG_NONE, EMG_SERVO_ERROR, EMG_FZ }
 
- Public Types inherited from hrp::Body
enum  ExtraJointType
 
- Public Types inherited from RTC::RTObject_impl
typedef ExecutionContextActionListener ECActionListener
 
typedef ExecutionContextActionListenerType ECActionListenerType
 
typedef PostComponentActionListener PostCompActionListener
 
typedef PostComponentActionListenerType PostCompActionListenerType
 
typedef PreComponentActionListener PreCompActionListener
 
typedef PreComponentActionListenerType PreCompActionListenerType
 

Public Member Functions

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< intgetJointGroup (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 ()
 
LightcreateLight (Link *link, int lightType, const std::string &name)
 
SensorcreateSensor (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 ()
 
Linkjoint (int id) const
 
const std::vector< Link *> & joints () const
 
Lightlight (const std::string &name)
 
Linklink (int index) const
 
Linklink (const std::string &name) const
 
const LinkTraverselinks () const
 
const LinkTraverselinkTraverse () 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)
 
LinkrootLink () const
 
Sensorsensor (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 ()
 
- Public Member Functions inherited from hrp::Referenced
 Referenced ()
 
virtual ~Referenced ()
 
- Public Member Functions inherited from RTC::DataFlowComponentBase
 DataFlowComponentBase (Manager *manager)
 
void init ()
 
virtual ~DataFlowComponentBase (void)
 
- Public Member Functions inherited from RTC::RTObject_impl
ReturnCode_t activate (RTC::UniqueId ec_id)
 
void addConfigurationParamListener (ConfigurationParamListenerType type, ConfigurationParamListener *listener, bool autoclean=true)
 
ConfigurationParamListeneraddConfigurationParamListener (ConfigurationParamListenerType listener_type, Listener &obj, void(Listener::*memfunc)(const char *, const char *))
 
void addConfigurationSetListener (ConfigurationSetListenerType type, ConfigurationSetListener *listener, bool autoclean=true)
 
ConfigurationSetListeneraddConfigurationSetListener (ConfigurationSetListenerType listener_type, Listener &obj, void(Listener::*memfunc)(const coil::Properties &config_set))
 
void addConfigurationSetNameListener (ConfigurationSetNameListenerType type, ConfigurationSetNameListener *listener, bool autoclean=true)
 
ConfigurationSetNameListeneraddConfigurationSetNameListener (ConfigurationSetNameListenerType type, Listener &obj, void(Listener::*memfunc)(const char *))
 
void addExecutionContextActionListener (ECActionListenerType listener_type, ECActionListener *listener, bool autoclean=true)
 
ECActionListeneraddExecutionContextActionListener (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)
 
PortActionListeneraddPortActionListener (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)
 
PortConnectListeneraddPortConnectListener (PortConnectListenerType listener_type, Listener &obj, void(Listener::*memfunc)(const char *, ConnectorProfile &))
 
void addPortConnectRetListener (PortConnectRetListenerType listener_type, PortConnectRetListener *listener, bool autoclean=true)
 
PortConnectRetListeneraddPortConnectRetListener (PortConnectRetListenerType listener_type, Listener &obj, void(Listener::*memfunc)(const char *, ConnectorProfile &, ReturnCode_t))
 
void addPostComponentActionListener (PostComponentActionListenerType listener_type, PostComponentActionListener *listener, bool autoclean=true)
 
PostComponentActionListeneraddPostComponentActionListener (PostCompActionListenerType listener_type, Listener &obj, void(Listener::*memfunc)(UniqueId ec_id, ReturnCode_t ret))
 
void addPreComponentActionListener (PreComponentActionListenerType listener_type, PreComponentActionListener *listener, bool autoclean=true)
 
PreComponentActionListeneraddPreComponentActionListener (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 ExecutionContextListget_owned_contexts ()
 
virtual SDOPackage::OrganizationList * get_owned_organizations ()
 
virtual ExecutionContextListget_participating_contexts ()
 
virtual PortServiceListget_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::NVListget_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::PropertiesgetProperties ()
 
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)
 

Static Public Member Functions

static void moduleInit (RTC::Manager *)
 
- Static Public Member Functions inherited from hrp::Body
static BodyInterfacebodyInterface ()
 

Public Attributes

int m_emergencyId
 
BodyRTC::emg_reason m_emergencyReason
 
std::vector< double > m_servoErrorLimit
 
- Public Attributes inherited from hrp::Body
 EJ_XY
 
 EJ_XYZ
 
 EJ_Z
 
std::vector< ExtraJointextraJoints
 

Private Attributes

std::vector< hrp::Vector3accels
 
std::vector< double > angles
 
std::vector< OpenHRP::RobotHardwareService::SwitchStatus > calib_status
 
std::vector< double > commands
 
int dummy
 
std::vector< hrp::dvector6forces
 
std::vector< hrp::Vector3gyros
 
std::vector< InPortHandlerBase * > m_inports
 
std::map< std::string, std::vector< int > > m_jointGroups
 
hrp::Vector3 m_lastServoOn_p
 
hrp::Matrix33 m_lastServoOn_R
 
std::vector< OutPortHandlerBase * > m_outports
 
bool m_resetPosition
 
RTC::CorbaPort m_RobotHardwareServicePort
 
RobotHardwareServicePort m_service0
 
std::vector< OpenHRP::RobotHardwareService::SwitchStatus > power_status
 
std::vector< OpenHRP::RobotHardwareService::SwitchStatus > servo_status
 

Static Private Attributes

static const char * bodyrtc_spec []
 

Additional Inherited Members

- Protected Member Functions inherited from hrp::Referenced
int refCounter ()
 
- Protected Member Functions inherited from RTC::RTObject_impl
virtual ReturnCode_t onAborting (RTC::UniqueId exec_handle)
 
void onAddPort (const PortProfile &pprof)
 
void onAttachExecutionContext (UniqueId ec_id)
 
void onDetachExecutionContext (UniqueId ec_id)
 
virtual ReturnCode_t onError (RTC::UniqueId exec_handle)
 
virtual ReturnCode_t onExecute (RTC::UniqueId exec_handle)
 
virtual ReturnCode_t onFinalize ()
 
virtual ReturnCode_t onInitialize ()
 
virtual ReturnCode_t onRateChanged (RTC::UniqueId exec_handle)
 
void onRemovePort (const PortProfile &pprof)
 
virtual ReturnCode_t onReset (RTC::UniqueId exec_handle)
 
virtual ReturnCode_t onShutdown (RTC::UniqueId exec_handle)
 
virtual ReturnCode_t onStartup (RTC::UniqueId exec_handle)
 
virtual ReturnCode_t onStateUpdate (RTC::UniqueId exec_handle)
 
void postOnAborting (UniqueId ec_id, ReturnCode_t ret)
 
void postOnActivated (UniqueId ec_id, ReturnCode_t ret)
 
void postOnDeactivated (UniqueId ec_id, ReturnCode_t ret)
 
void postOnError (UniqueId ec_id, ReturnCode_t ret)
 
void postOnExecute (UniqueId ec_id, ReturnCode_t ret)
 
void postOnFinalize (UniqueId ec_id, ReturnCode_t ret)
 
void postOnInitialize (UniqueId ec_id, ReturnCode_t ret)
 
void postOnRateChanged (UniqueId ec_id, ReturnCode_t ret)
 
void postOnReset (UniqueId ec_id, ReturnCode_t ret)
 
void postOnShutdown (UniqueId ec_id, ReturnCode_t ret)
 
void postOnStartup (UniqueId ec_id, ReturnCode_t ret)
 
void postOnStateUpdate (UniqueId ec_id, ReturnCode_t ret)
 
void preOnAborting (UniqueId ec_id)
 
void preOnActivated (UniqueId ec_id)
 
void preOnDeactivated (UniqueId ec_id)
 
void preOnError (UniqueId ec_id)
 
void preOnExecute (UniqueId ec_id)
 
void preOnFinalize (UniqueId ec_id)
 
void preOnInitialize (UniqueId ec_id)
 
void preOnRateChanged (UniqueId ec_id)
 
void preOnReset (UniqueId ec_id)
 
void preOnShutdown (UniqueId ec_id)
 
void preOnStartup (UniqueId ec_id)
 
void preOnStateUpdate (UniqueId ec_id)
 
void shutdown ()
 
- Protected Attributes inherited from RTC::RTObject_impl
ComponentActionListeners m_actionListeners
 
ConfigAdmin m_configsets
 
bool m_created
 
std::vector< ExecutionContextBase *> m_eclist
 
ExecutionContextServiceList m_ecMine
 
ExecutionContextServiceList m_ecOther
 
bool m_exiting
 
std::vector< InPortBase *> m_inports
 
RTObject_var m_objref
 
std::vector< OutPortBase *> m_outports
 
Managerm_pManager
 
CORBA::ORB_var m_pORB
 
PortAdmin m_portAdmin
 
PortConnectListeners m_portconnListeners
 
PortableServer::POA_var m_pPOA
 
ComponentProfile m_profile
 
coil::Properties m_properties
 
SDOPackage::Configuration_var m_pSdoConfig
 
SDOPackage::Configuration_implm_pSdoConfigImpl
 
bool m_readAll
 
bool m_readAllCompletion
 
SDOPackage::OrganizationList m_sdoOrganizations
 
SDOPackage::OrganizationList m_sdoOwnedOrganizations
 
SdoServiceAdmin m_sdoservice
 
SDOPackage::NVList m_sdoStatus
 
bool m_writeAll
 
bool m_writeAllCompletion
 
Logger rtclog
 

Detailed Description

Definition at line 60 of file BodyRTC.h.

Member Enumeration Documentation

◆ emg_reason

Enumerator
EMG_NONE 
EMG_SERVO_ERROR 
EMG_FZ 

Definition at line 122 of file BodyRTC.h.

Constructor & Destructor Documentation

◆ BodyRTC()

BodyRTC::BodyRTC ( RTC::Manager manager = &RTC::Manager::instance())

Definition at line 29 of file BodyRTC.cpp.

◆ ~BodyRTC()

BodyRTC::~BodyRTC ( void  )
virtual

Definition at line 39 of file BodyRTC.cpp.

Member Function Documentation

◆ addJointGroup()

int BodyRTC::addJointGroup ( const char *  gname,
const std::vector< int jids 
)
inline

Definition at line 90 of file BodyRTC.h.

◆ checkEmergency()

bool BodyRTC::checkEmergency ( emg_reason o_reason,
int o_id 
)

Definition at line 494 of file BodyRTC.cpp.

◆ createInPort()

void BodyRTC::createInPort ( const std::string &  config)

Definition at line 140 of file BodyRTC.cpp.

◆ createOutPort()

void BodyRTC::createOutPort ( const std::string &  config)

Definition at line 219 of file BodyRTC.cpp.

◆ getJointGroup()

std::vector<int> BodyRTC::getJointGroup ( const char *  gname)
inline

Definition at line 89 of file BodyRTC.h.

◆ getStatus()

void BodyRTC::getStatus ( OpenHRP::RobotHardwareService::RobotState *  rs)

Definition at line 414 of file BodyRTC.cpp.

◆ getStatus2()

void BodyRTC::getStatus2 ( OpenHRP::RobotHardwareService::RobotState2 *  rs)

Definition at line 459 of file BodyRTC.cpp.

◆ lengthDigitalInput()

int BodyRTC::lengthDigitalInput ( )

◆ lengthDigitalOutput()

int BodyRTC::lengthDigitalOutput ( )

◆ moduleInit()

void BodyRTC::moduleInit ( RTC::Manager manager)
static

Definition at line 732 of file BodyRTC.cpp.

◆ names2ids()

bool BodyRTC::names2ids ( const std::vector< std::string > &  i_names,
std::vector< int > &  o_ids 
)

Definition at line 397 of file BodyRTC.cpp.

◆ onActivated()

RTC::ReturnCode_t BodyRTC::onActivated ( RTC::UniqueId  ec_id)
inlinevirtual

Reimplemented from RTC::RTObject_impl.

Definition at line 68 of file BodyRTC.h.

◆ onDeactivated()

RTC::ReturnCode_t BodyRTC::onDeactivated ( RTC::UniqueId  ec_id)
inlinevirtual

Reimplemented from RTC::RTObject_impl.

Definition at line 72 of file BodyRTC.h.

◆ postOneStep()

bool BodyRTC::postOneStep ( )

Definition at line 569 of file BodyRTC.cpp.

◆ power() [1/2]

bool BodyRTC::power ( int  jid,
bool  turnon 
)
inline

Definition at line 93 of file BodyRTC.h.

◆ power() [2/2]

bool BodyRTC::power ( const char *  jname,
bool  turnon 
)

Definition at line 629 of file BodyRTC.cpp.

◆ preOneStep()

bool BodyRTC::preOneStep ( )

Definition at line 521 of file BodyRTC.cpp.

◆ readCalibState()

int BodyRTC::readCalibState ( const int  i)
inline

Definition at line 104 of file BodyRTC.h.

◆ readDataPorts()

void BodyRTC::readDataPorts ( )

Definition at line 57 of file BodyRTC.cpp.

◆ readDigitalInput()

bool BodyRTC::readDigitalInput ( char *  o_din)

◆ readDigitalOutput()

bool BodyRTC::readDigitalOutput ( char *  o_dout)

◆ readPowerState()

int BodyRTC::readPowerState ( const int  i)
inline

Definition at line 105 of file BodyRTC.h.

◆ readServoState()

int BodyRTC::readServoState ( const int  i)
inline

Definition at line 106 of file BodyRTC.h.

◆ resetPosition()

bool BodyRTC::resetPosition ( )
inline

Definition at line 139 of file BodyRTC.h.

◆ servo() [1/2]

bool BodyRTC::servo ( const char *  jname,
bool  turnon 
)

Definition at line 605 of file BodyRTC.cpp.

◆ servo() [2/2]

bool BodyRTC::servo ( int  jid,
bool  turnon 
)
inline

Definition at line 95 of file BodyRTC.h.

◆ setServoErrorLimit()

bool BodyRTC::setServoErrorLimit ( const char *  i_jname,
double  i_limit 
)

Definition at line 462 of file BodyRTC.cpp.

◆ setup()

RTC::ReturnCode_t BodyRTC::setup ( )

Definition at line 65 of file BodyRTC.cpp.

◆ writeDataPorts()

void BodyRTC::writeDataPorts ( double  time)

Definition at line 50 of file BodyRTC.cpp.

◆ writeDigitalOutput()

bool BodyRTC::writeDigitalOutput ( const char *  i_dout)

◆ writeDigitalOutputWithMask()

bool BodyRTC::writeDigitalOutputWithMask ( const char *  i_dout,
const char *  i_mask 
)

Member Data Documentation

◆ accels

std::vector<hrp::Vector3> BodyRTC::accels
private

Definition at line 159 of file BodyRTC.h.

◆ angles

std::vector<double> BodyRTC::angles
private

Definition at line 157 of file BodyRTC.h.

◆ bodyrtc_spec

const char * BodyRTC::bodyrtc_spec
staticprivate
Initial value:
=
{
"implementation_id", "BodyRTC",
"type_name", "BodyRTC",
"description", "BodyRTC component",
"version", "0.1",
"vendor", "AIST",
"category", "Generic",
"activity_type", "DataFlowComponent",
"max_instance", "10",
"language", "C++",
"lang_type", "compile",
""
}

Definition at line 145 of file BodyRTC.h.

◆ calib_status

std::vector<OpenHRP::RobotHardwareService::SwitchStatus> BodyRTC::calib_status
private

Definition at line 162 of file BodyRTC.h.

◆ commands

std::vector<double> BodyRTC::commands
private

Definition at line 158 of file BodyRTC.h.

◆ dummy

int BodyRTC::dummy
private

Definition at line 172 of file BodyRTC.h.

◆ forces

std::vector<hrp::dvector6> BodyRTC::forces
private

Definition at line 161 of file BodyRTC.h.

◆ gyros

std::vector<hrp::Vector3> BodyRTC::gyros
private

Definition at line 160 of file BodyRTC.h.

◆ m_emergencyId

int BodyRTC::m_emergencyId

Definition at line 142 of file BodyRTC.h.

◆ m_emergencyReason

BodyRTC::emg_reason BodyRTC::m_emergencyReason

Definition at line 141 of file BodyRTC.h.

◆ m_inports

std::vector<InPortHandlerBase *> BodyRTC::m_inports
private

Definition at line 147 of file BodyRTC.h.

◆ m_jointGroups

std::map<std::string, std::vector<int> > BodyRTC::m_jointGroups
private

Definition at line 165 of file BodyRTC.h.

◆ m_lastServoOn_p

hrp::Vector3 BodyRTC::m_lastServoOn_p
private

Definition at line 169 of file BodyRTC.h.

◆ m_lastServoOn_R

hrp::Matrix33 BodyRTC::m_lastServoOn_R
private

Definition at line 170 of file BodyRTC.h.

◆ m_outports

std::vector<OutPortHandlerBase *> BodyRTC::m_outports
private

Definition at line 150 of file BodyRTC.h.

◆ m_resetPosition

bool BodyRTC::m_resetPosition
private

Definition at line 168 of file BodyRTC.h.

◆ m_RobotHardwareServicePort

RTC::CorbaPort BodyRTC::m_RobotHardwareServicePort
private

Definition at line 153 of file BodyRTC.h.

◆ m_service0

RobotHardwareServicePort BodyRTC::m_service0
private

Definition at line 154 of file BodyRTC.h.

◆ m_servoErrorLimit

std::vector<double> BodyRTC::m_servoErrorLimit

Definition at line 128 of file BodyRTC.h.

◆ power_status

std::vector<OpenHRP::RobotHardwareService::SwitchStatus> BodyRTC::power_status
private

Definition at line 164 of file BodyRTC.h.

◆ servo_status

std::vector<OpenHRP::RobotHardwareService::SwitchStatus> BodyRTC::servo_status
private

Definition at line 163 of file BodyRTC.h.


The documentation for this class was generated from the following files:


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Sat Dec 17 2022 03:52:21