#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 (hardware_interface::HardwareInterface *hw, bool allow_unprogrammed=true) |
| 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, uint16_t address, void *buffer, uint16_t length, AddrMode addrMode) |
| int | readWriteData (EthercatCom *com, uint16_t address, void *buffer, uint16_t length, AddrMode addrMode) |
| virtual bool | unpackState (unsigned char *this_buffer, unsigned char *prev_buffer) |
| int | writeData (EthercatCom *com, uint16_t address, void const *buffer, uint16_t length, AddrMode addrMode) |
| virtual | ~EthercatDevice () |
Static Public Member Functions | |
| static int | readData (EthercatCom *com, EtherCAT_SlaveHandler *sh, uint16_t address, void *buffer, uint16_t length, AddrMode addrMode=FIXED_ADDR) |
| Read data from device ESC. | |
| static int | readWriteData (EthercatCom *com, EtherCAT_SlaveHandler *sh, uint16_t address, void *buffer, uint16_t length, AddrMode addrMode=FIXED_ADDR) |
| Read then write data to ESC. | |
| static int | writeData (EthercatCom *com, EtherCAT_SlaveHandler *sh, uint16_t address, void const *buffer, uint16_t length, AddrMode addrMode=FIXED_ADDR) |
| 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 136 of file ethercat_device.h.
Definition at line 206 of file ethercat_device.h.
Definition at line 357 of file ethercat_device.cpp.
| virtual EthercatDevice::~EthercatDevice | ( | ) | [inline, virtual] |
Definition at line 148 of file ethercat_device.h.
| void EthercatDevice::collectDiagnostics | ( | EthercatCom * | com | ) | [virtual] |
Definition at line 381 of file ethercat_device.cpp.
| void EthercatDevice::construct | ( | EtherCAT_SlaveHandler * | sh, |
| int & | start_address | ||
| ) | [virtual] |
< Construct EtherCAT device
Construct non-EtherCAT device
Definition at line 350 of file ethercat_device.cpp.
| virtual void EthercatDevice::construct | ( | ros::NodeHandle & | nh | ) | [inline, virtual] |
Definition at line 143 of file ethercat_device.h.
| 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. |
Definition at line 586 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 567 of file ethercat_device.cpp.
| virtual int EthercatDevice::initialize | ( | hardware_interface::HardwareInterface * | hw, |
| bool | allow_unprogrammed = true |
||
| ) | [inline, virtual] |
Definition at line 153 of file ethercat_device.h.
| 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.\ |
Definition at line 607 of file ethercat_device.cpp.
| virtual void EthercatDevice::packCommand | ( | unsigned char * | buffer, |
| bool | halt, | ||
| bool | reset | ||
| ) | [inline, virtual] |
| reset | when asserted this will clear diagnostic error conditions device safety disable |
| halt | while asserted will disable actuator, usually by disabling H-bridge |
Definition at line 161 of file ethercat_device.h.
| 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. |
Definition at line 201 of file ethercat_device.h.
| int EthercatDevice::readData | ( | EthercatCom * | com, |
| EtherCAT_SlaveHandler * | sh, | ||
| uint16_t | address, | ||
| void * | buffer, | ||
| uint16_t | length, | ||
| AddrMode | addrMode = FIXED_ADDR |
||
| ) | [static] |
Read data from device ESC.
Definition at line 462 of file ethercat_device.cpp.
| int EthercatDevice::readData | ( | EthercatCom * | com, |
| uint16_t | address, | ||
| void * | buffer, | ||
| uint16_t | length, | ||
| AddrMode | addrMode | ||
| ) | [inline] |
Definition at line 227 of file ethercat_device.h.
| int EthercatDevice::readWriteData | ( | EthercatCom * | com, |
| EtherCAT_SlaveHandler * | sh, | ||
| uint16_t | address, | ||
| void * | buffer, | ||
| uint16_t | length, | ||
| AddrMode | addrMode = FIXED_ADDR |
||
| ) | [static] |
Read then write data to ESC.
Definition at line 409 of file ethercat_device.cpp.
| int EthercatDevice::readWriteData | ( | EthercatCom * | com, |
| uint16_t | address, | ||
| void * | buffer, | ||
| uint16_t | length, | ||
| AddrMode | addrMode | ||
| ) | [inline] |
Definition at line 238 of file ethercat_device.h.
| virtual bool EthercatDevice::unpackState | ( | unsigned char * | this_buffer, |
| unsigned char * | prev_buffer | ||
| ) | [inline, virtual] |
Definition at line 164 of file ethercat_device.h.
| int EthercatDevice::writeData | ( | EthercatCom * | com, |
| EtherCAT_SlaveHandler * | sh, | ||
| uint16_t | address, | ||
| void const * | buffer, | ||
| uint16_t | length, | ||
| AddrMode | addrMode = FIXED_ADDR |
||
| ) | [static] |
Write data to device ESC.
Definition at line 515 of file ethercat_device.cpp.
| int EthercatDevice::writeData | ( | EthercatCom * | com, |
| uint16_t | address, | ||
| void const * | buffer, | ||
| uint16_t | length, | ||
| AddrMode | addrMode | ||
| ) | [inline] |
Definition at line 216 of file ethercat_device.h.
| unsigned int EthercatDevice::command_size_ |
Definition at line 247 of file ethercat_device.h.
Definition at line 258 of file ethercat_device.h.
Definition at line 262 of file ethercat_device.h.
| pthread_mutex_t EthercatDevice::diagnosticsLock_ |
Definition at line 259 of file ethercat_device.h.
| unsigned EthercatDevice::newDiagnosticsIndex_ |
Definition at line 256 of file ethercat_device.h.
| pthread_mutex_t EthercatDevice::newDiagnosticsIndexLock_ |
Definition at line 257 of file ethercat_device.h.
Definition at line 246 of file ethercat_device.h.
| unsigned int EthercatDevice::status_size_ |
Definition at line 248 of file ethercat_device.h.
Definition at line 244 of file ethercat_device.h.