|
void | construct (EtherCAT_SlaveHandler *sh, int &start_address) |
| < Construct EtherCAT device More...
|
|
void | diagnostics (diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *) |
| For EtherCAT device that only publish one EtherCAT Status message. If sub-class implements multiDiagnostics() then diagnostics() is not used. More...
|
|
int | initialize (pr2_hardware_interface::HardwareInterface *, bool) |
|
| ~WG014 () |
|
virtual void | collectDiagnostics (EthercatCom *com) |
|
virtual void | construct (ros::NodeHandle &nh) |
|
| EthercatDevice () |
|
void | ethercatDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &d, unsigned numPorts) |
| Adds diagnostic information for EtherCAT ports. More...
|
|
virtual void | multiDiagnostics (vector< diagnostic_msgs::DiagnosticStatus > &vec, unsigned char *buffer) |
| For EtherCAT devices that publish more than one EtherCAT Status message. If sub-class implements multiDiagnostics() then diagnostics() is not used. More...
|
|
virtual void | packCommand (unsigned char *buffer, bool halt, bool reset) |
|
virtual bool | publishTrace (const string &reason, unsigned level, unsigned delay) |
| Asks device to publish (motor) trace. Only works for devices that support it. More...
|
|
int | readData (EthercatCom *com, EC_UINT address, void *buffer, EC_UINT length, AddrMode addrMode) |
|
int | readWriteData (EthercatCom *com, EC_UINT address, void *buffer, EC_UINT length, AddrMode addrMode) |
|
virtual bool | unpackState (unsigned char *this_buffer, unsigned char *prev_buffer) |
|
int | writeData (EthercatCom *com, EC_UINT address, void const *buffer, EC_UINT length, AddrMode addrMode) |
|
virtual | ~EthercatDevice () |
|
|
static int | readData (EthercatCom *com, EtherCAT_SlaveHandler *sh, EC_UINT address, void *buffer, EC_UINT length, AddrMode addrMode) |
| Read data from device ESC. More...
|
|
static int | readWriteData (EthercatCom *com, EtherCAT_SlaveHandler *sh, EC_UINT address, void *buffer, EC_UINT length, AddrMode addrMode) |
| Read then write data to ESC. More...
|
|
static int | writeData (EthercatCom *com, EtherCAT_SlaveHandler *sh, EC_UINT address, void const *buffer, EC_UINT length, AddrMode addrMode) |
| Write data to device ESC. More...
|
|
enum EthercatDevice::AddrMode | __attribute__ |
|
unsigned int | command_size_ |
|
EthercatDeviceDiagnostics | deviceDiagnostics [2] |
|
diagnostic_updater::DiagnosticStatusWrapper | diagnostic_status_ |
|
pthread_mutex_t | diagnosticsLock_ |
|
unsigned | newDiagnosticsIndex_ |
|
pthread_mutex_t | newDiagnosticsIndexLock_ |
|
EtherCAT_SlaveHandler * | sh_ |
|
unsigned int | status_size_ |
|
bool | use_ros_ |
|
Definition at line 40 of file wg014.h.