WG0X Class Reference

#include <wg0x.h>

Inheritance diagram for WG0X:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void collectDiagnostics (EthercatCom *com)
void construct (EtherCAT_SlaveHandler *sh, int &start_address)
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.
virtual int initialize (pr2_hardware_interface::HardwareInterface *, bool allow_unprogrammed=true)
void packCommand (unsigned char *buffer, bool halt, bool reset)
void program (WG0XActuatorInfo *)
bool publishTrace (const string &reason, unsigned level, unsigned delay)
 Asks device to publish (motor) trace. Only works for devices that support it.
bool unpackState (unsigned char *this_buffer, unsigned char *prev_buffer)
 WG0X ()
virtual ~WG0X ()

Static Public Member Functions

static double calcEncoderVelocity (int32_t new_position, uint32_t new_timestamp, int32_t old_position, uint32_t old_timestamp)
static int32_t positionDiff (int32_t new_position, int32_t old_position)
static ros::Duration timediffToDuration (int32_t timediff_usec)
static int32_t timestampDiff (uint32_t new_timestamp, uint32_t old_timestamp)

Protected Types

enum  {
  MODE_OFF = 0x00, MODE_ENABLE = (1 << 0), MODE_CURRENT = (1 << 1), MODE_SAFETY_RESET = (1 << 4),
  MODE_SAFETY_LOCKOUT = (1 << 5), MODE_UNDERVOLTAGE = (1 << 6), MODE_RESET = (1 << 7)
}
enum  { NO_CALIBRATION = 0, CONTROLLER_CALIBRATION = 1, SAVED_CALIBRATION = 2 }
enum  AppRamStatus { APP_RAM_PRESENT = 1, APP_RAM_MISSING = 2, APP_RAM_NOT_APPLICABLE = 3 }
 

Different possible states for application ram on device.

More...

Protected Member Functions

void clearErrorFlags (void)
bool initializeMotorModel (pr2_hardware_interface::HardwareInterface *hw, const string &device_description, double max_pwm_ratio, double board_resistance, bool poor_measured_motor_voltage)
 Allocates and initialized motor trace for WG0X devices than use it (WG006, WG005).
void publishGeneralDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &d)
void publishMailboxDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &d)
bool readAppRam (EthercatCom *com, double &zero_offset)
int readEeprom (EthercatCom *com)
int readMailbox (EthercatCom *com, unsigned address, void *data, unsigned length)
 Read data from WG0X local bus using mailbox communication.
int sendSpiCommand (EthercatCom *com, WG0XSpiEepromCmd const *cmd)
bool verifyChecksum (const void *buffer, unsigned size)
bool verifyState (WG0XStatus *this_status, WG0XStatus *prev_status)
bool writeAppRam (EthercatCom *com, double zero_offset)
int writeEeprom (EthercatCom *com)
int writeMailbox (EthercatCom *com, unsigned address, void const *data, unsigned length)
 Write data to WG0X local bus using mailbox communication.

Static Protected Member Functions

static string modeString (uint8_t mode)
static string safetyDisableString (uint8_t status)
static bool timestamp_jump (uint32_t timestamp, uint32_t last_timestamp, uint32_t amount)

Protected Attributes

pr2_hardware_interface::Actuator actuator_
WG0XActuatorInfo actuator_info_
AppRamStatus app_ram_status_
uint8_t board_major_
 Printed circuit board revision (for this value 0=='A', 1=='B').
uint8_t board_minor_
 Printed circuit assembly revision.
double cached_zero_offset_
int calibration_status_
WG0XConfigInfo config_info_
pr2_hardware_interface::DigitalOut digital_out_
bool fpga_internal_reset_detected_
uint8_t fw_major_
uint8_t fw_minor_
bool has_error_
bool in_lockout_
unsigned last_num_encoder_errors_
 Number of encoder errors the last time motors were reset.
uint16_t max_board_temperature_
uint16_t max_bridge_temperature_
double max_current_
 min(board current limit, actuator current limit)
bool resetting_
ros::Duration sample_timestamp_
bool status_checksum_error_
bool timestamp_jump_detected_
bool too_many_dropped_packets_

Static Protected Attributes

static const int PWM_MAX = 0x4000

Private Types

enum  { LIMIT_SENSOR_0_STATE = (1 << 0), LIMIT_SENSOR_1_STATE = (1 << 1), LIMIT_ON_TO_OFF = (1 << 2), LIMIT_OFF_TO_ON = (1 << 3) }
enum  {
  SAFETY_DISABLED = (1 << 0), SAFETY_UNDERVOLTAGE = (1 << 1), SAFETY_OVER_CURRENT = (1 << 2), SAFETY_BOARD_OVER_TEMP = (1 << 3),
  SAFETY_HBRIDGE_OVER_TEMP = (1 << 4), SAFETY_OPERATIONAL = (1 << 5), SAFETY_WATCHDOG = (1 << 6)
}

Private Member Functions

bool _readMailboxRepeatRequest (EthercatCom *com)
bool clearReadMailbox (EthercatCom *com)
 Clears read mailbox by reading first and last byte.
void diagnoseMailboxError (EthercatCom *com)
 Runs diagnostic on read and write mailboxes.
bool lockMailbox ()
bool lockWG0XDiagnostics ()
int readMailbox_ (EthercatCom *com, unsigned address, void *data, unsigned length)
 Internal function.
bool readMailboxInternal (EthercatCom *com, void *data, unsigned length)
 Reads data from read mailbox.
bool readMailboxRepeatRequest (EthercatCom *com)
bool tryLockWG0XDiagnostics ()
void unlockMailbox ()
void unlockWG0XDiagnostics ()
bool verifyDeviceStateForMailboxOperation ()
bool waitForReadMailboxReady (EthercatCom *com)
 Waits until read mailbox is full or timeout.
bool waitForWriteMailboxReady (EthercatCom *com)
 Waits until write mailbox is empty or timeout.
int writeMailbox_ (EthercatCom *com, unsigned address, void const *data, unsigned length)
 Internal function.
bool writeMailboxInternal (EthercatCom *com, void const *data, unsigned length)
 Writes data to mailbox.

Private Attributes

int consecutive_drops_
bool disable_motor_model_checking_
int drops_
uint32_t last_last_timestamp_
uint32_t last_timestamp_
MbxDiagnostics mailbox_diagnostics_
pthread_mutex_t mailbox_lock_
MbxDiagnostics mailbox_publish_diagnostics_
int max_consecutive_drops_
MotorModelmotor_model_
ethercat_hardware::MotorTraceSample motor_trace_sample_
pr2_hardware_interface::DigitalOut publish_motor_trace_
WG0XDiagnostics wg0x_collect_diagnostics_
pthread_mutex_t wg0x_diagnostics_lock_
WG0XDiagnostics wg0x_publish_diagnostics_

Static Private Attributes

static const int ACTUATOR_INFO_PAGE = 4095
static const unsigned COMMAND_PHY_ADDR = 0x1000
static const unsigned MBX_COMMAND_PHY_ADDR = 0x1400
static const unsigned MBX_COMMAND_SIZE = 512
static const unsigned MBX_COMMAND_SYNCMAN_NUM = 2
static const unsigned MBX_STATUS_PHY_ADDR = 0x2400
static const unsigned MBX_STATUS_SIZE = 512
static const unsigned MBX_STATUS_SYNCMAN_NUM = 3
static const unsigned PDO_COMMAND_SYNCMAN_NUM = 0
static const unsigned PDO_STATUS_SYNCMAN_NUM = 1
static const unsigned PRESSURE_PHY_ADDR = 0x2200
static const unsigned STATUS_PHY_ADDR = 0x2000

Detailed Description

Definition at line 461 of file wg0x.h.


Member Enumeration Documentation

anonymous enum [protected]
Enumerator:
MODE_OFF 
MODE_ENABLE 
MODE_CURRENT 
MODE_SAFETY_RESET 
MODE_SAFETY_LOCKOUT 
MODE_UNDERVOLTAGE 
MODE_RESET 

Definition at line 494 of file wg0x.h.

anonymous enum [protected]
Enumerator:
NO_CALIBRATION 
CONTROLLER_CALIBRATION 
SAVED_CALIBRATION 

Definition at line 519 of file wg0x.h.

anonymous enum [private]
Enumerator:
LIMIT_SENSOR_0_STATE 
LIMIT_SENSOR_1_STATE 
LIMIT_ON_TO_OFF 
LIMIT_OFF_TO_ON 

Definition at line 598 of file wg0x.h.

anonymous enum [private]
Enumerator:
SAFETY_DISABLED 
SAFETY_UNDERVOLTAGE 
SAFETY_OVER_CURRENT 
SAFETY_BOARD_OVER_TEMP 
SAFETY_HBRIDGE_OVER_TEMP 
SAFETY_OPERATIONAL 
SAFETY_WATCHDOG 

Definition at line 606 of file wg0x.h.

enum WG0X::AppRamStatus [protected]

Different possible states for application ram on device.

Enumerator:
APP_RAM_PRESENT 
APP_RAM_MISSING 
APP_RAM_NOT_APPLICABLE 

Definition at line 537 of file wg0x.h.


Constructor & Destructor Documentation

WG0X::WG0X (  ) 

Definition at line 199 of file wg0x.cpp.

WG0X::~WG0X (  )  [virtual]

Definition at line 223 of file wg0x.cpp.


Member Function Documentation

bool WG0X::_readMailboxRepeatRequest ( EthercatCom com  )  [private]

Definition at line 1909 of file wg0x.cpp.

double WG0X::calcEncoderVelocity ( int32_t  new_position,
uint32_t  new_timestamp,
int32_t  old_position,
uint32_t  old_timestamp 
) [static]

Returns velocity in encoder ticks per second.

Timestamp assumed to be in microseconds Accounts for wrapping of timestamp values and position values.

Definition at line 1063 of file wg0x.cpp.

void WG0X::clearErrorFlags ( void   )  [protected]

Definition at line 711 of file wg0x.cpp.

bool WG0X::clearReadMailbox ( EthercatCom com  )  [private]

Clears read mailbox by reading first and last byte.

Mailbox lock should be held when this function is called.

Parameters:
com used to perform communication with device
Returns:
returns true for success, false for failure

Definition at line 1594 of file wg0x.cpp.

void WG0X::collectDiagnostics ( EthercatCom com  )  [virtual]

Reimplemented from EthercatDevice.

Definition at line 1239 of file wg0x.cpp.

void WG0X::construct ( EtherCAT_SlaveHandler *  sh,
int &  start_address 
) [virtual]

Reimplemented from EthercatDevice.

Reimplemented in WG021.

Definition at line 248 of file wg0x.cpp.

void WG0X::diagnoseMailboxError ( EthercatCom com  )  [private]

Runs diagnostic on read and write mailboxes.

Collects and data from mailbox control registers.

Todo:
not implemented yet
Parameters:
com used to perform communication with device
Returns:
returns true for success, false for failure

Definition at line 1581 of file wg0x.cpp.

void WG0X::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:
d Diagnostics status wrapper.
buffer Pointer to slave process data.

Reimplemented from EthercatDevice.

Reimplemented in WG06, and WG021.

Definition at line 2519 of file wg0x.cpp.

int WG0X::initialize ( pr2_hardware_interface::HardwareInterface *  hw,
bool  allow_unprogrammed = true 
) [virtual]

Implements EthercatDevice.

Reimplemented in WG05, WG06, and WG021.

Definition at line 562 of file wg0x.cpp.

bool WG0X::initializeMotorModel ( pr2_hardware_interface::HardwareInterface *  hw,
const string &  device_description,
double  max_pwm_ratio,
double  board_resistance,
bool  poor_measured_motor_voltage 
) [protected]

Allocates and initialized motor trace for WG0X devices than use it (WG006, WG005).

Definition at line 499 of file wg0x.cpp.

bool WG0X::lockMailbox (  )  [private]

Definition at line 2223 of file wg0x.cpp.

bool WG0X::lockWG0XDiagnostics (  )  [private]

Definition at line 2243 of file wg0x.cpp.

string WG0X::modeString ( uint8_t  mode  )  [static, protected]

Definition at line 2372 of file wg0x.cpp.

void WG0X::packCommand ( unsigned char *  buffer,
bool  halt,
bool  reset 
) [virtual]
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 from EthercatDevice.

Reimplemented in WG05, WG06, and WG021.

Definition at line 720 of file wg0x.cpp.

int32_t WG0X::positionDiff ( int32_t  new_position,
int32_t  old_position 
) [static]

Returns (new_position - old_position). Accounts for wrap-around of 32-bit position values.

It is assumed that each position value is exactly 32bit and can wrap from -2147483648 to +2147483647.

Definition at line 1052 of file wg0x.cpp.

void WG0X::program ( WG0XActuatorInfo info  ) 

Definition at line 1414 of file wg0x.cpp.

void WG0X::publishGeneralDiagnostics ( diagnostic_updater::DiagnosticStatusWrapper &  d  )  [protected]

Definition at line 2420 of file wg0x.cpp.

void WG0X::publishMailboxDiagnostics ( diagnostic_updater::DiagnosticStatusWrapper &  d  )  [protected]

Definition at line 2406 of file wg0x.cpp.

bool WG0X::publishTrace ( const string &  reason,
unsigned  level,
unsigned  delay 
) [virtual]

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

Definition at line 1177 of file wg0x.cpp.

bool WG0X::readAppRam ( EthercatCom com,
double &  zero_offset 
) [protected]

Definition at line 1325 of file wg0x.cpp.

int WG0X::readEeprom ( EthercatCom com  )  [protected]

Definition at line 1383 of file wg0x.cpp.

int WG0X::readMailbox ( EthercatCom com,
unsigned  address,
void *  data,
unsigned  length 
) [protected]

Read data from WG0X local bus using mailbox communication.

Internally a localbus read is done in two parts. First, a mailbox write of a command header that include local bus address and length. Second, a mailbox read of the result.

Parameters:
com used to perform communication with device
address WG0X (FPGA) local bus address to read from
data pointer to buffer where read data can be stored, must be at least length in size
length amount of data to read, limited at 511 bytes.
Returns:
returns zero for success, non-zero for failure

Definition at line 2129 of file wg0x.cpp.

int WG0X::readMailbox_ ( EthercatCom com,
unsigned  address,
void *  data,
unsigned  length 
) [private]

Internal function.

Aguments are the same as readMailbox() except that this assumes the mailbox lock is held.

Definition at line 2148 of file wg0x.cpp.

bool WG0X::readMailboxInternal ( EthercatCom com,
void *  data,
unsigned  length 
) [private]

Reads data from read mailbox.

Will try to conserve bandwidth by reading length bytes of data and last byte of mailbox. Mailbox lock should be held when this function is called.

Parameters:
com used to perform communication with device
data pointer to buffer where read data is stored.
length amount of data to read from mailbox
Returns:
returns true for success, false for failure

Definition at line 1998 of file wg0x.cpp.

bool WG0X::readMailboxRepeatRequest ( EthercatCom com  )  [private]

Definition at line 1899 of file wg0x.cpp.

string WG0X::safetyDisableString ( uint8_t  status  )  [static, protected]

Definition at line 2352 of file wg0x.cpp.

int WG0X::sendSpiCommand ( EthercatCom com,
WG0XSpiEepromCmd const *  cmd 
) [protected]

Definition at line 1345 of file wg0x.cpp.

ros::Duration WG0X::timediffToDuration ( int32_t  timediff_usec  )  [static]

Convert timestamp difference to ros::Duration. Timestamp is assumed to be in microseconds

It is assumed that each timestamps is exactly 32bit and can wrap around from 0xFFFFFFFF back to 0. In this case 1 - 4294967295 should equal 2 not -4294967294. (Note : 0xFFFFFFFF = 4294967295)

Definition at line 1038 of file wg0x.cpp.

bool WG0X::timestamp_jump ( uint32_t  timestamp,
uint32_t  last_timestamp,
uint32_t  amount 
) [static, protected]

Definition at line 1073 of file wg0x.cpp.

int32_t WG0X::timestampDiff ( uint32_t  new_timestamp,
uint32_t  old_timestamp 
) [static]

Returns (new_timestamp - old_timestamp). Accounts for wrapping of timestamp values.

It is assumed that each timestamps is exactly 32bit and can wrap around from 0xFFFFFFFF back to 0. In this case 1 - 4294967295 should equal 2 not -4294967294. (Note : 0xFFFFFFFF = 4294967295)

Definition at line 1027 of file wg0x.cpp.

bool WG0X::tryLockWG0XDiagnostics (  )  [private]

Definition at line 2255 of file wg0x.cpp.

void WG0X::unlockMailbox (  )  [private]

Definition at line 2234 of file wg0x.cpp.

void WG0X::unlockWG0XDiagnostics (  )  [private]

Definition at line 2270 of file wg0x.cpp.

bool WG0X::unpackState ( unsigned char *  this_buffer,
unsigned char *  prev_buffer 
) [virtual]

Reimplemented from EthercatDevice.

Reimplemented in WG05, WG06, and WG021.

Definition at line 935 of file wg0x.cpp.

bool WG0X::verifyChecksum ( const void *  buffer,
unsigned  size 
) [protected]

Definition at line 986 of file wg0x.cpp.

bool WG0X::verifyDeviceStateForMailboxOperation (  )  [private]

Definition at line 1559 of file wg0x.cpp.

bool WG0X::verifyState ( WG0XStatus this_status,
WG0XStatus prev_status 
) [protected]

Definition at line 1079 of file wg0x.cpp.

bool WG0X::waitForReadMailboxReady ( EthercatCom com  )  [private]

Waits until read mailbox is full or timeout.

Wait times out after 100msec. Mailbox lock should be held when this function is called.

Parameters:
com used to perform communication with device
Returns:
returns true for success, false for failure or timeout

Definition at line 1676 of file wg0x.cpp.

bool WG0X::waitForWriteMailboxReady ( EthercatCom com  )  [private]

Waits until write mailbox is empty or timeout.

Wait times out after 100msec. Mailbox lock should be held when this function is called.

Parameters:
com used to perform communication with device
Returns:
returns true for success, false for failure or timeout

Definition at line 1728 of file wg0x.cpp.

bool WG0X::writeAppRam ( EthercatCom com,
double  zero_offset 
) [protected]

Definition at line 1314 of file wg0x.cpp.

int WG0X::writeEeprom ( EthercatCom com  )  [protected]
int WG0X::writeMailbox ( EthercatCom com,
unsigned  address,
void const *  data,
unsigned  length 
) [protected]

Write data to WG0X local bus using mailbox communication.

First, this puts a command header that include local bus address and length in write mailbox. Second it waits until device actually empties write mailbox.

Parameters:
com used to perform communication with device
address WG0X (FPGA) local bus address to write data to
data pointer to buffer where write data is stored, must be at least length in size
length amount of data to write, limited at 507 bytes
Returns:
returns zero for success, non-zero for failure

Definition at line 2292 of file wg0x.cpp.

int WG0X::writeMailbox_ ( EthercatCom com,
unsigned  address,
void const *  data,
unsigned  length 
) [private]

Internal function.

Aguments are the same as writeMailbox() except that this assumes the mailbox lock is held.

Definition at line 2312 of file wg0x.cpp.

bool WG0X::writeMailboxInternal ( EthercatCom com,
void const *  data,
unsigned  length 
) [private]

Writes data to mailbox.

Will try to conserve bandwidth by only length bytes of data and last byte of mailbox. Mailbox lock should be held when this function is called.

Parameters:
com used to perform communication with device
data pointer to buffer where read data is stored.
length amount of data to read from mailbox
Returns:
returns true for success, false for failure

Definition at line 1783 of file wg0x.cpp.


Member Data Documentation

pr2_hardware_interface::Actuator WG0X::actuator_ [protected]

Definition at line 491 of file wg0x.h.

Definition at line 487 of file wg0x.h.

const int WG0X::ACTUATOR_INFO_PAGE = 4095 [static, private]

Definition at line 619 of file wg0x.h.

Definition at line 538 of file wg0x.h.

uint8_t WG0X::board_major_ [protected]

Printed circuit board revision (for this value 0=='A', 1=='B').

Definition at line 484 of file wg0x.h.

uint8_t WG0X::board_minor_ [protected]

Printed circuit assembly revision.

Definition at line 485 of file wg0x.h.

double WG0X::cached_zero_offset_ [protected]

Definition at line 518 of file wg0x.h.

int WG0X::calibration_status_ [protected]

Definition at line 520 of file wg0x.h.

const unsigned WG0X::COMMAND_PHY_ADDR = 0x1000 [static, private]

Definition at line 585 of file wg0x.h.

Definition at line 488 of file wg0x.h.

int WG0X::consecutive_drops_ [private]

Definition at line 632 of file wg0x.h.

pr2_hardware_interface::DigitalOut WG0X::digital_out_ [protected]

Definition at line 492 of file wg0x.h.

Definition at line 624 of file wg0x.h.

int WG0X::drops_ [private]

Definition at line 631 of file wg0x.h.

Definition at line 514 of file wg0x.h.

uint8_t WG0X::fw_major_ [protected]

Definition at line 482 of file wg0x.h.

uint8_t WG0X::fw_minor_ [protected]

Definition at line 483 of file wg0x.h.

bool WG0X::has_error_ [protected]

Definition at line 509 of file wg0x.h.

bool WG0X::in_lockout_ [protected]

Definition at line 507 of file wg0x.h.

uint32_t WG0X::last_last_timestamp_ [private]

Definition at line 630 of file wg0x.h.

unsigned WG0X::last_num_encoder_errors_ [protected]

Number of encoder errors the last time motors were reset.

Definition at line 521 of file wg0x.h.

uint32_t WG0X::last_timestamp_ [private]

Definition at line 629 of file wg0x.h.

Definition at line 569 of file wg0x.h.

pthread_mutex_t WG0X::mailbox_lock_ [private]

Definition at line 568 of file wg0x.h.

Definition at line 570 of file wg0x.h.

uint16_t WG0X::max_board_temperature_ [protected]

Definition at line 510 of file wg0x.h.

uint16_t WG0X::max_bridge_temperature_ [protected]

Definition at line 510 of file wg0x.h.

Definition at line 633 of file wg0x.h.

double WG0X::max_current_ [protected]

min(board current limit, actuator current limit)

Definition at line 489 of file wg0x.h.

const unsigned WG0X::MBX_COMMAND_PHY_ADDR = 0x1400 [static, private]

Definition at line 588 of file wg0x.h.

const unsigned WG0X::MBX_COMMAND_SIZE = 512 [static, private]

Definition at line 589 of file wg0x.h.

const unsigned WG0X::MBX_COMMAND_SYNCMAN_NUM = 2 [static, private]

Definition at line 595 of file wg0x.h.

const unsigned WG0X::MBX_STATUS_PHY_ADDR = 0x2400 [static, private]

Definition at line 590 of file wg0x.h.

const unsigned WG0X::MBX_STATUS_SIZE = 512 [static, private]

Definition at line 591 of file wg0x.h.

const unsigned WG0X::MBX_STATUS_SYNCMAN_NUM = 3 [static, private]

Definition at line 596 of file wg0x.h.

Definition at line 623 of file wg0x.h.

Definition at line 625 of file wg0x.h.

const unsigned WG0X::PDO_COMMAND_SYNCMAN_NUM = 0 [static, private]

Definition at line 593 of file wg0x.h.

const unsigned WG0X::PDO_STATUS_SYNCMAN_NUM = 1 [static, private]

Definition at line 594 of file wg0x.h.

const unsigned WG0X::PRESSURE_PHY_ADDR = 0x2200 [static, private]

Definition at line 587 of file wg0x.h.

pr2_hardware_interface::DigitalOut WG0X::publish_motor_trace_ [private]

Definition at line 626 of file wg0x.h.

const int WG0X::PWM_MAX = 0x4000 [static, protected]

Definition at line 562 of file wg0x.h.

bool WG0X::resetting_ [protected]

Definition at line 508 of file wg0x.h.

ros::Duration WG0X::sample_timestamp_ [protected]

The ros::Duration timestamp measures the time since the ethercat process started. It is generated by accumulating diffs between 32bit device timestamps. Device timestamps are assumed to be in microseconds, so 32bit timestamp will overflow every 72 minutes, ros::Duration (int32_t secs, int32_t nsecs) should overflow will overflow after 68 years

Definition at line 528 of file wg0x.h.

bool WG0X::status_checksum_error_ [protected]

Definition at line 512 of file wg0x.h.

const unsigned WG0X::STATUS_PHY_ADDR = 0x2000 [static, private]

Definition at line 586 of file wg0x.h.

Definition at line 513 of file wg0x.h.

Definition at line 511 of file wg0x.h.

Definition at line 640 of file wg0x.h.

pthread_mutex_t WG0X::wg0x_diagnostics_lock_ [private]

Definition at line 638 of file wg0x.h.

Definition at line 639 of file wg0x.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


ethercat_hardware
Author(s): Maintained by Derek King (email: dking@willowgarage.com)
autogenerated on Fri Jan 11 09:11:23 2013