#include <ethercat_device.h>
Public Types | |
enum | AddrMode { FIXED_ADDR = 0, POSITIONAL_ADDR = 1 } |
Public Member Functions | |
virtual void | collectDiagnostics (EthercatCom *com) |
virtual void | construct (EtherCAT_SlaveHandler *sh, int &start_address) |
< Construct EtherCAT device | |
virtual void | construct (ros::NodeHandle &nh) |
virtual void | diagnostics (diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *buffer) |
For EtherCAT device that only publish one EtherCAT Status message. If sub-class implements multiDiagnostics() then diagnostics() is not used. | |
EthercatDevice () | |
void | ethercatDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &d, unsigned numPorts) |
Adds diagnostic information for EtherCAT ports. | |
virtual int | initialize (pr2_hardware_interface::HardwareInterface *, bool allow_unprogrammed=0)=0 |
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. | |
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. | |
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 Public Member Functions | |
static int | readData (EthercatCom *com, EtherCAT_SlaveHandler *sh, EC_UINT address, void *buffer, EC_UINT length, AddrMode addrMode) |
Read data from device ESC. | |
static int | readWriteData (EthercatCom *com, EtherCAT_SlaveHandler *sh, EC_UINT address, void *buffer, EC_UINT length, AddrMode addrMode) |
Read then write data to ESC. | |
static int | writeData (EthercatCom *com, EtherCAT_SlaveHandler *sh, EC_UINT address, void const *buffer, EC_UINT length, AddrMode addrMode) |
Write data to device ESC. | |
Public Attributes | |
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 133 of file ethercat_device.h.
Definition at line 189 of file ethercat_device.h.
Definition at line 342 of file ethercat_device.cpp.
EthercatDevice::~EthercatDevice | ( | ) | [virtual] |
Definition at line 364 of file ethercat_device.cpp.
void EthercatDevice::collectDiagnostics | ( | EthercatCom * | com | ) | [virtual] |
Reimplemented in WG0X.
Definition at line 369 of file ethercat_device.cpp.
void EthercatDevice::construct | ( | EtherCAT_SlaveHandler * | sh, |
int & | start_address | ||
) | [virtual] |
void EthercatDevice::construct | ( | ros::NodeHandle & | nh | ) | [virtual] |
Definition at line 336 of file ethercat_device.cpp.
void EthercatDevice::diagnostics | ( | diagnostic_updater::DiagnosticStatusWrapper & | d, |
unsigned char * | buffer | ||
) | [virtual] |
For EtherCAT device that only publish one EtherCAT Status message. If sub-class implements multiDiagnostics() then diagnostics() is not used.
d | Diagnostics status wrapper. |
buffer | Pointer to slave process data. |
Reimplemented in WG0X, WG021, EK1122, and WG014.
Definition at line 557 of file ethercat_device.cpp.
void EthercatDevice::ethercatDiagnostics | ( | diagnostic_updater::DiagnosticStatusWrapper & | d, |
unsigned | numPorts | ||
) |
Adds diagnostic information for EtherCAT ports.
d | EtherCAT port diagnostics information will be appended. |
buffer | Number of communication ports slave has. |
Definition at line 538 of file ethercat_device.cpp.
virtual int EthercatDevice::initialize | ( | pr2_hardware_interface::HardwareInterface * | , |
bool | allow_unprogrammed = 0 |
||
) | [pure virtual] |
void EthercatDevice::multiDiagnostics | ( | vector< diagnostic_msgs::DiagnosticStatus > & | vec, |
unsigned char * | buffer | ||
) | [virtual] |
For EtherCAT devices that publish more than one EtherCAT Status message. If sub-class implements multiDiagnostics() then diagnostics() is not used.
vec | Vector of diagnostics status messages. Slave appends one or more new diagnostic status'. |
buffer | Pointer to slave process data. |
Reimplemented in WG06.
Definition at line 578 of file ethercat_device.cpp.
virtual void EthercatDevice::packCommand | ( | unsigned char * | buffer, |
bool | halt, | ||
bool | reset | ||
) | [inline, virtual] |
virtual bool EthercatDevice::publishTrace | ( | const string & | reason, |
unsigned | level, | ||
unsigned | delay | ||
) | [inline, virtual] |
Asks device to publish (motor) trace. Only works for devices that support it.
reason | Message to put in trace as reason. |
level | Level to put in trace (aka ERROR=2, WARN=1, OK=0) |
delay | Publish trace after delay cyles. For 1kHz realtime loop 1cycle = 1ms. |
Reimplemented in WG0X.
Definition at line 187 of file ethercat_device.h.
int EthercatDevice::readData | ( | EthercatCom * | com, |
EtherCAT_SlaveHandler * | sh, | ||
EC_UINT | address, | ||
void * | buffer, | ||
EC_UINT | length, | ||
AddrMode | addrMode | ||
) | [static] |
Read data from device ESC.
Definition at line 445 of file ethercat_device.cpp.
int EthercatDevice::readData | ( | EthercatCom * | com, |
EC_UINT | address, | ||
void * | buffer, | ||
EC_UINT | length, | ||
AddrMode | addrMode | ||
) | [inline] |
Definition at line 203 of file ethercat_device.h.
int EthercatDevice::readWriteData | ( | EthercatCom * | com, |
EtherCAT_SlaveHandler * | sh, | ||
EC_UINT | address, | ||
void * | buffer, | ||
EC_UINT | length, | ||
AddrMode | addrMode | ||
) | [static] |
Read then write data to ESC.
Definition at line 398 of file ethercat_device.cpp.
int EthercatDevice::readWriteData | ( | EthercatCom * | com, |
EC_UINT | address, | ||
void * | buffer, | ||
EC_UINT | length, | ||
AddrMode | addrMode | ||
) | [inline] |
Definition at line 211 of file ethercat_device.h.
virtual bool EthercatDevice::unpackState | ( | unsigned char * | this_buffer, |
unsigned char * | prev_buffer | ||
) | [inline, virtual] |
int EthercatDevice::writeData | ( | EthercatCom * | com, |
EtherCAT_SlaveHandler * | sh, | ||
EC_UINT | address, | ||
void const * | buffer, | ||
EC_UINT | length, | ||
AddrMode | addrMode | ||
) | [static] |
Write data to device ESC.
Definition at line 492 of file ethercat_device.cpp.
int EthercatDevice::writeData | ( | EthercatCom * | com, |
EC_UINT | address, | ||
void const * | buffer, | ||
EC_UINT | length, | ||
AddrMode | addrMode | ||
) | [inline] |
Definition at line 195 of file ethercat_device.h.
Reimplemented in WG0X.
unsigned int EthercatDevice::command_size_ |
Definition at line 218 of file ethercat_device.h.
Definition at line 229 of file ethercat_device.h.
Definition at line 233 of file ethercat_device.h.
pthread_mutex_t EthercatDevice::diagnosticsLock_ |
Definition at line 230 of file ethercat_device.h.
unsigned EthercatDevice::newDiagnosticsIndex_ |
Definition at line 227 of file ethercat_device.h.
pthread_mutex_t EthercatDevice::newDiagnosticsIndexLock_ |
Definition at line 228 of file ethercat_device.h.
EtherCAT_SlaveHandler* EthercatDevice::sh_ |
Definition at line 217 of file ethercat_device.h.
unsigned int EthercatDevice::status_size_ |
Definition at line 219 of file ethercat_device.h.
Definition at line 215 of file ethercat_device.h.