#include <ek1122.h>
Public Types | |
enum | { PRODUCT_CODE = 0x4622c52 } |
Public Types inherited from EthercatDevice | |
enum | AddrMode { FIXED_ADDR =0, POSITIONAL_ADDR =1 } |
Public Member Functions | |
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) |
~EK1122 () | |
Public Member Functions inherited from EthercatDevice | |
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 () |
Additional Inherited Members | |
Static Public Member Functions inherited from 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... | |
Public Attributes inherited from EthercatDevice | |
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_ |
EK1122::~EK1122 | ( | ) |
Definition at line 49 of file ek1122.cpp.
|
virtual |
< Construct EtherCAT device
Construct non-EtherCAT device
Reimplemented from EthercatDevice.
Definition at line 42 of file ek1122.cpp.
|
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 from EthercatDevice.
Definition at line 60 of file ek1122.cpp.
|
virtual |
Implements EthercatDevice.
Definition at line 55 of file ek1122.cpp.