#include <ethercat_device.h>
|
virtual void | collectDiagnostics (EthercatCom *com) |
|
virtual void | construct (EtherCAT_SlaveHandler *sh, int &start_address) |
| < Construct EtherCAT device More...
|
|
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. More...
|
|
| EthercatDevice () |
|
void | ethercatDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &d, unsigned numPorts) |
| Adds diagnostic information for EtherCAT ports. More...
|
|
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. 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...
|
|
Definition at line 133 of file ethercat_device.h.
◆ AddrMode
◆ EthercatDevice()
EthercatDevice::EthercatDevice |
( |
| ) |
|
◆ ~EthercatDevice()
EthercatDevice::~EthercatDevice |
( |
| ) |
|
|
virtual |
◆ collectDiagnostics()
void EthercatDevice::collectDiagnostics |
( |
EthercatCom * |
com | ) |
|
|
virtual |
◆ construct() [1/2]
void EthercatDevice::construct |
( |
EtherCAT_SlaveHandler * |
sh, |
|
|
int & |
start_address |
|
) |
| |
|
virtual |
◆ construct() [2/2]
◆ diagnostics()
◆ ethercatDiagnostics()
Adds diagnostic information for EtherCAT ports.
- Parameters
-
d | EtherCAT port diagnostics information will be appended. |
buffer | Number of communication ports slave has. |
Definition at line 538 of file ethercat_device.cpp.
◆ initialize()
◆ multiDiagnostics()
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.
- Parameters
-
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.
◆ packCommand()
virtual void EthercatDevice::packCommand |
( |
unsigned char * |
buffer, |
|
|
bool |
halt, |
|
|
bool |
reset |
|
) |
| |
|
inlinevirtual |
- Parameters
-
reset | when asserted this will clear diagnostic error conditions device safety disable |
halt | while asserted will disable actuator, usually by disabling H-bridge |
Reimplemented in WG0X, WG06, WG021, and WG05.
Definition at line 151 of file ethercat_device.h.
◆ publishTrace()
virtual bool EthercatDevice::publishTrace |
( |
const string & |
reason, |
|
|
unsigned |
level, |
|
|
unsigned |
delay |
|
) |
| |
|
inlinevirtual |
Asks device to publish (motor) trace. Only works for devices that support it.
- Parameters
-
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. |
- Returns
- Return true if device support publishing trace. False, if not.
Reimplemented in WG0X.
Definition at line 187 of file ethercat_device.h.
◆ readData() [1/2]
int EthercatDevice::readData |
( |
EthercatCom * |
com, |
|
|
EC_UINT |
address, |
|
|
void * |
buffer, |
|
|
EC_UINT |
length, |
|
|
AddrMode |
addrMode |
|
) |
| |
|
inline |
◆ readData() [2/2]
int EthercatDevice::readData |
( |
EthercatCom * |
com, |
|
|
EtherCAT_SlaveHandler * |
sh, |
|
|
EC_UINT |
address, |
|
|
void * |
buffer, |
|
|
EC_UINT |
length, |
|
|
AddrMode |
addrMode |
|
) |
| |
|
static |
◆ readWriteData() [1/2]
int EthercatDevice::readWriteData |
( |
EthercatCom * |
com, |
|
|
EC_UINT |
address, |
|
|
void * |
buffer, |
|
|
EC_UINT |
length, |
|
|
AddrMode |
addrMode |
|
) |
| |
|
inline |
◆ readWriteData() [2/2]
int EthercatDevice::readWriteData |
( |
EthercatCom * |
com, |
|
|
EtherCAT_SlaveHandler * |
sh, |
|
|
EC_UINT |
address, |
|
|
void * |
buffer, |
|
|
EC_UINT |
length, |
|
|
AddrMode |
addrMode |
|
) |
| |
|
static |
◆ unpackState()
virtual bool EthercatDevice::unpackState |
( |
unsigned char * |
this_buffer, |
|
|
unsigned char * |
prev_buffer |
|
) |
| |
|
inlinevirtual |
◆ writeData() [1/2]
int EthercatDevice::writeData |
( |
EthercatCom * |
com, |
|
|
EC_UINT |
address, |
|
|
void const * |
buffer, |
|
|
EC_UINT |
length, |
|
|
AddrMode |
addrMode |
|
) |
| |
|
inline |
◆ writeData() [2/2]
int EthercatDevice::writeData |
( |
EthercatCom * |
com, |
|
|
EtherCAT_SlaveHandler * |
sh, |
|
|
EC_UINT |
address, |
|
|
void const * |
buffer, |
|
|
EC_UINT |
length, |
|
|
AddrMode |
addrMode |
|
) |
| |
|
static |
◆ __attribute__
◆ command_size_
unsigned int EthercatDevice::command_size_ |
◆ deviceDiagnostics
◆ diagnostic_status_
◆ diagnosticsLock_
pthread_mutex_t EthercatDevice::diagnosticsLock_ |
◆ newDiagnosticsIndex_
unsigned EthercatDevice::newDiagnosticsIndex_ |
◆ newDiagnosticsIndexLock_
pthread_mutex_t EthercatDevice::newDiagnosticsIndexLock_ |
◆ sh_
EtherCAT_SlaveHandler* EthercatDevice::sh_ |
◆ status_size_
unsigned int EthercatDevice::status_size_ |
◆ use_ros_
bool EthercatDevice::use_ros_ |
The documentation for this class was generated from the following files: