Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | List of all members
EthercatDevice Class Referenceabstract

#include <ethercat_device.h>

Inheritance diagram for EthercatDevice:
Inheritance graph
[legend]

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 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 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. 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

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_
 

Detailed Description

Definition at line 133 of file ethercat_device.h.

Member Enumeration Documentation

◆ AddrMode

Enumerator
FIXED_ADDR 
POSITIONAL_ADDR 

Definition at line 189 of file ethercat_device.h.

Constructor & Destructor Documentation

◆ EthercatDevice()

EthercatDevice::EthercatDevice ( )

Definition at line 342 of file ethercat_device.cpp.

◆ ~EthercatDevice()

EthercatDevice::~EthercatDevice ( )
virtual

Definition at line 364 of file ethercat_device.cpp.

Member Function Documentation

◆ collectDiagnostics()

void EthercatDevice::collectDiagnostics ( EthercatCom com)
virtual

Reimplemented in WG0X.

Definition at line 369 of file ethercat_device.cpp.

◆ construct() [1/2]

void EthercatDevice::construct ( EtherCAT_SlaveHandler *  sh,
int &  start_address 
)
virtual

< Construct EtherCAT device

Construct non-EtherCAT device

Reimplemented in WG0X, WG06, WG021, WG05, EK1122, and WG014.

Definition at line 331 of file ethercat_device.cpp.

◆ construct() [2/2]

void EthercatDevice::construct ( ros::NodeHandle nh)
virtual

Definition at line 336 of file ethercat_device.cpp.

◆ diagnostics()

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.

Parameters
dDiagnostics status wrapper.
bufferPointer to slave process data.

Reimplemented in WG0X, WG021, EK1122, and WG014.

Definition at line 557 of file ethercat_device.cpp.

◆ ethercatDiagnostics()

void EthercatDevice::ethercatDiagnostics ( diagnostic_updater::DiagnosticStatusWrapper d,
unsigned  numPorts 
)

Adds diagnostic information for EtherCAT ports.

Parameters
dEtherCAT port diagnostics information will be appended.
bufferNumber of communication ports slave has.

Definition at line 538 of file ethercat_device.cpp.

◆ initialize()

virtual int EthercatDevice::initialize ( pr2_hardware_interface::HardwareInterface ,
bool  allow_unprogrammed = 0 
)
pure virtual

Implemented in WG0X, WG06, WG021, WG05, EK1122, and WG014.

◆ 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
vecVector of diagnostics status messages. Slave appends one or more new diagnostic status'.
bufferPointer 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
resetwhen asserted this will clear diagnostic error conditions device safety disable
haltwhile 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
reasonMessage to put in trace as reason.
levelLevel to put in trace (aka ERROR=2, WARN=1, OK=0)
delayPublish 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,
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.

◆ readData() [2/2]

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.

◆ readWriteData() [1/2]

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.

◆ readWriteData() [2/2]

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.

◆ unpackState()

virtual bool EthercatDevice::unpackState ( unsigned char *  this_buffer,
unsigned char *  prev_buffer 
)
inlinevirtual

Reimplemented in WG0X, WG06, WG021, and WG05.

Definition at line 153 of file ethercat_device.h.

◆ writeData() [1/2]

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.

◆ writeData() [2/2]

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.

Member Data Documentation

◆ __attribute__

enum EthercatDevice::AddrMode EthercatDevice::__attribute__

◆ command_size_

unsigned int EthercatDevice::command_size_

Definition at line 218 of file ethercat_device.h.

◆ deviceDiagnostics

EthercatDeviceDiagnostics EthercatDevice::deviceDiagnostics[2]

Definition at line 229 of file ethercat_device.h.

◆ diagnostic_status_

diagnostic_updater::DiagnosticStatusWrapper EthercatDevice::diagnostic_status_

Definition at line 233 of file ethercat_device.h.

◆ diagnosticsLock_

pthread_mutex_t EthercatDevice::diagnosticsLock_

Definition at line 230 of file ethercat_device.h.

◆ newDiagnosticsIndex_

unsigned EthercatDevice::newDiagnosticsIndex_

Definition at line 227 of file ethercat_device.h.

◆ newDiagnosticsIndexLock_

pthread_mutex_t EthercatDevice::newDiagnosticsIndexLock_

Definition at line 228 of file ethercat_device.h.

◆ sh_

EtherCAT_SlaveHandler* EthercatDevice::sh_

Definition at line 217 of file ethercat_device.h.

◆ status_size_

unsigned int EthercatDevice::status_size_

Definition at line 219 of file ethercat_device.h.

◆ use_ros_

bool EthercatDevice::use_ros_

Definition at line 215 of file ethercat_device.h.


The documentation for this class was generated from the following files:


ethercat_hardware
Author(s): Rob Wheeler , Derek King
autogenerated on Tue Mar 28 2023 02:10:20