Public Types | Public Member Functions | Protected Attributes | List of all members
WG014 Class Reference

#include <wg014.h>

Inheritance diagram for WG014:
Inheritance graph
[legend]

Public Types

enum  { PRODUCT_CODE = 6805014 }
 
- 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)
 
 ~WG014 ()
 
- 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 ()
 

Protected Attributes

uint8_t board_major_
 
uint8_t board_minor_
 
uint8_t fw_major_
 
uint8_t fw_minor_
 

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_
 

Detailed Description

Definition at line 40 of file wg014.h.

Member Enumeration Documentation

anonymous enum
Enumerator
PRODUCT_CODE 

Definition at line 48 of file wg014.h.

Constructor & Destructor Documentation

WG014::~WG014 ( )

Definition at line 54 of file wg014.cpp.

Member Function Documentation

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

< Construct EtherCAT device

Construct non-EtherCAT device

Reimplemented from EthercatDevice.

Definition at line 42 of file wg014.cpp.

void WG014::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 from EthercatDevice.

Definition at line 66 of file wg014.cpp.

int WG014::initialize ( pr2_hardware_interface::HardwareInterface ,
bool   
)
virtual

Implements EthercatDevice.

Definition at line 60 of file wg014.cpp.

Member Data Documentation

uint8_t WG014::board_major_
protected

Definition at line 53 of file wg014.h.

uint8_t WG014::board_minor_
protected

Definition at line 54 of file wg014.h.

uint8_t WG014::fw_major_
protected

Definition at line 51 of file wg014.h.

uint8_t WG014::fw_minor_
protected

Definition at line 52 of file wg014.h.


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


ethercat_hardware
Author(s): Rob Wheeler , Derek King
autogenerated on Fri Mar 15 2019 02:53:29