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

#include <wg0x.h>

Inheritance diagram for WG0X:
Inheritance graph
[legend]

Public Member Functions

virtual void collectDiagnostics (EthercatCom *com)
 
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...
 
virtual int initialize (pr2_hardware_interface::HardwareInterface *, bool allow_unprogrammed=true)
 
void packCommand (unsigned char *buffer, bool halt, bool reset)
 
bool program (EthercatCom *com, const WG0XActuatorInfo &actutor_info)
 Programs acutator and heating parameters into device EEPROM. More...
 
bool program (EthercatCom *com, const MotorHeatingModelParametersEepromConfig &heating_config)
 Programs motor heating parameters into device EEPROM. More...
 
bool publishTrace (const string &reason, unsigned level, unsigned delay)
 Asks device to publish (motor) trace. Only works for devices that support it. More...
 
bool readActuatorInfoFromEeprom (EthercatCom *com, WG0XActuatorInfo &actuator_info)
 Reads actuator info from eeprom. More...
 
bool readMotorHeatingModelParametersFromEeprom (EthercatCom *com, MotorHeatingModelParametersEepromConfig &config)
 Reads actuator info from eeprom. More...
 
bool unpackState (unsigned char *this_buffer, unsigned char *prev_buffer)
 
 WG0X ()
 
virtual ~WG0X ()
 
- Public Member Functions inherited from EthercatDevice
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...
 
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)
 
int writeData (EthercatCom *com, EC_UINT address, void const *buffer, EC_UINT length, AddrMode addrMode)
 
virtual ~EthercatDevice ()
 

Static Public Member Functions

static double calcEncoderVelocity (int32_t new_position, uint32_t new_timestamp, int32_t old_position, uint32_t old_timestamp)
 
static double convertRawTemperature (int16_t raw_temp)
 Converts raw 16bit temperature value returned by device into value in degress Celcius. More...
 
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)
 
- 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...
 

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  { WG05_PRODUCT_CODE = 6805005, WG06_PRODUCT_CODE = 6805006, WG021_PRODUCT_CODE = 6805021 }
 
enum  { NO_CALIBRATION =0, CONTROLLER_CALIBRATION =1, SAVED_CALIBRATION =2 }
 
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)
}
 
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 initializeMotorHeatingModel (bool allow_unprogrammed)
 
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) More...
 
bool lockWG0XDiagnostics ()
 
void publishGeneralDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &d)
 
void publishMailboxDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &d)
 
bool readAppRam (EthercatCom *com, double &zero_offset)
 
int readMailbox (EthercatCom *com, unsigned address, void *data, unsigned length)
 Read data from WG0X local bus using mailbox communication. More...
 
bool tryLockWG0XDiagnostics ()
 
void unlockWG0XDiagnostics ()
 
bool verifyChecksum (const void *buffer, unsigned size)
 
bool verifyState (WG0XStatus *this_status, WG0XStatus *prev_status)
 
bool writeAppRam (EthercatCom *com, double zero_offset)
 
int writeMailbox (EthercatCom *com, unsigned address, void const *data, unsigned length)
 Write data to WG0X local bus using mailbox communication. More...
 

Static Protected Member Functions

static void copyActuatorInfo (ethercat_hardware::ActuatorInfo &out, const WG0XActuatorInfo &in)
 Fills in ethercat_hardware::ActuatorInfo from WG0XActuatorInfo. More...
 
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

enum WG0X:: { ... }  __attribute__
 
pr2_hardware_interface::Actuator actuator_
 
WG0XActuatorInfo actuator_info_
 
ethercat_hardware::ActuatorInfo actuator_info_msg_
 
AppRamStatus app_ram_status_
 
uint8_t board_major_
 Printed circuit board revision (for this value 0=='A', 1=='B') More...
 
uint8_t board_minor_
 Printed circuit assembly revision. More...
 
double cached_zero_offset_
 
int calibration_status_
 
WG0XConfigInfo config_info_
 
int consecutive_drops_
 
pr2_hardware_interface::DigitalOut digital_out_
 
bool disable_motor_model_checking_
 
int drops_
 
ethercat_hardware::WGEeprom eeprom_
 Access to device eeprom. More...
 
bool encoder_errors_detected_
 
bool fpga_internal_reset_detected_
 
uint8_t fw_major_
 
uint8_t fw_minor_
 
bool has_error_
 
bool in_lockout_
 
uint32_t last_last_timestamp_
 
uint32_t last_timestamp_
 
ethercat_hardware::WGMailbox mailbox_
 Mailbox access to device. More...
 
uint16_t max_board_temperature_
 
uint16_t max_bridge_temperature_
 
int max_consecutive_drops_
 
double max_current_
 min(board current limit, actuator current limit) More...
 
boost::shared_ptr< ethercat_hardware::MotorHeatingModelmotor_heating_model_
 
MotorModelmotor_model_
 
ethercat_hardware::MotorTraceSample motor_trace_sample_
 
pr2_hardware_interface::DigitalOut publish_motor_trace_
 
bool resetting_
 
ros::Duration sample_timestamp_
 
bool status_checksum_error_
 
bool timestamp_jump_detected_
 
bool too_many_dropped_packets_
 
WG0XDiagnostics wg0x_collect_diagnostics_
 
pthread_mutex_t wg0x_diagnostics_lock_
 
WG0XDiagnostics wg0x_publish_diagnostics_
 

Static Protected Attributes

static const unsigned ACTUATOR_INFO_PAGE = 4095
 
static const unsigned COMMAND_PHY_ADDR = 0x1000
 
static boost::shared_ptr< ethercat_hardware::MotorHeatingModelCommonmotor_heating_model_common_
 
static const unsigned PDO_COMMAND_SYNCMAN_NUM = 0
 
static const unsigned PDO_STATUS_SYNCMAN_NUM = 1
 
static const int PWM_MAX = 0x4000
 
static const unsigned STATUS_PHY_ADDR = 0x2000
 

Additional Inherited Members

- Public Types inherited from EthercatDevice
enum  AddrMode { FIXED_ADDR =0, POSITIONAL_ADDR =1 }
 
- 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 234 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 273 of file wg0x.h.

anonymous enum
protected
Enumerator
WG05_PRODUCT_CODE 
WG06_PRODUCT_CODE 
WG021_PRODUCT_CODE 

Definition at line 284 of file wg0x.h.

anonymous enum
protected
Enumerator
NO_CALIBRATION 
CONTROLLER_CALIBRATION 
SAVED_CALIBRATION 

Definition at line 306 of file wg0x.h.

anonymous enum
protected
Enumerator
LIMIT_SENSOR_0_STATE 
LIMIT_SENSOR_1_STATE 
LIMIT_ON_TO_OFF 
LIMIT_OFF_TO_ON 

Definition at line 362 of file wg0x.h.

anonymous enum
protected
Enumerator
SAFETY_DISABLED 
SAFETY_UNDERVOLTAGE 
SAFETY_OVER_CURRENT 
SAFETY_BOARD_OVER_TEMP 
SAFETY_HBRIDGE_OVER_TEMP 
SAFETY_OPERATIONAL 
SAFETY_WATCHDOG 

Definition at line 370 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 323 of file wg0x.h.

Constructor & Destructor Documentation

WG0X::WG0X ( )

Definition at line 156 of file wg0x.cpp.

WG0X::~WG0X ( )
virtual

Definition at line 189 of file wg0x.cpp.

Member Function Documentation

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 720 of file wg0x.cpp.

void WG0X::clearErrorFlags ( void  )
protected

Definition at line 548 of file wg0x.cpp.

void WG0X::collectDiagnostics ( EthercatCom com)
virtual

Reimplemented from EthercatDevice.

Definition at line 884 of file wg0x.cpp.

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

< Construct EtherCAT device

Construct non-EtherCAT device

Reimplemented from EthercatDevice.

Definition at line 197 of file wg0x.cpp.

double WG0X::convertRawTemperature ( int16_t  raw_temp)
static

Converts raw 16bit temperature value returned by device into value in degress Celcius.

Parameters
raw_tempRaw 16bit temperature value return by device
Returns
Temperature in degrees Celcius

Definition at line 735 of file wg0x.cpp.

void WG0X::copyActuatorInfo ( ethercat_hardware::ActuatorInfo &  out,
const WG0XActuatorInfo in 
)
staticprotected

Fills in ethercat_hardware::ActuatorInfo from WG0XActuatorInfo.

WG0XAcuatorInfo is a packed structure that comes directly from the device EEPROM. ethercat_hardware::ActuatorInfo is a ROS message type that is used by both motor model and motor heating model.

Definition at line 219 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
dDiagnostics status wrapper.
bufferPointer to slave process data.

Reimplemented from EthercatDevice.

Definition at line 1323 of file wg0x.cpp.

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

Implements EthercatDevice.

Reimplemented in WG06, WG021, and WG05.

Definition at line 394 of file wg0x.cpp.

bool WG0X::initializeMotorHeatingModel ( bool  allow_unprogrammed)
protected

Definition at line 295 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 237 of file wg0x.cpp.

bool WG0X::lockWG0XDiagnostics ( )
protected

Definition at line 1106 of file wg0x.cpp.

string WG0X::modeString ( uint8_t  mode)
staticprotected

Definition at line 1188 of file wg0x.cpp.

void WG0X::packCommand ( unsigned char *  buffer,
bool  halt,
bool  reset 
)
virtual
Parameters
resetwhen asserted this will clear diagnostic error conditions device safety disable
haltwhile asserted will disable actuator, usually by disabling H-bridge

Reimplemented from EthercatDevice.

Definition at line 562 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 709 of file wg0x.cpp.

bool WG0X::program ( EthercatCom com,
const WG0XActuatorInfo actutor_info 
)

Programs acutator and heating parameters into device EEPROM.

WG0X devices store configuaration info in EEPROM. This configuration information contains information such as device name, motor parameters, and encoder parameters.

Originally, devices only stored ActuatorInfo in EEPROM. However, later we discovered that in extreme cases, certain motors may overheat. To prevent motor overheating, a model is used to estimate motor winding temperature and stop motor if temperature gets too high. However, the new motor heating model needs more motor parameters than were originally stored in eeprom.

Parameters
comEtherCAT communication class used for communicating with device
actutor_infoActuator information to be stored in device EEPROM
actutor_infoMotor heating motor information to be stored in device EEPROM
Returns
true if there is success, false if there is an error

Definition at line 1050 of file wg0x.cpp.

bool WG0X::program ( EthercatCom com,
const MotorHeatingModelParametersEepromConfig heating_config 
)

Programs motor heating parameters into device EEPROM.

Originally, devices only stored ActuatorInfo in EEPROM. However, later we discovered that in extreme cases, certain motors may overheat. To prevent motor overheating, a model is used to estimate motor winding temperature and stop motor if temperature gets too high. However, the new motor heating model needs more motor parameters than were originally stored in eeprom.

Parameters
comEtherCAT communication class used for communicating with device
heating_configMotor heating model parameters to be stored in device EEPROM
Returns
true if there is success, false if there is an error

Definition at line 1076 of file wg0x.cpp.

void WG0X::publishGeneralDiagnostics ( diagnostic_updater::DiagnosticStatusWrapper d)
protected

Definition at line 1222 of file wg0x.cpp.

void WG0X::publishMailboxDiagnostics ( diagnostic_updater::DiagnosticStatusWrapper d)
protected
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
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 from EthercatDevice.

Definition at line 873 of file wg0x.cpp.

bool WG0X::readActuatorInfoFromEeprom ( EthercatCom com,
WG0XActuatorInfo actuator_info 
)

Reads actuator info from eeprom.

Parameters
comEtherCAT communication class used for communicating with device
acuator_infoStructure where actuator info will be stored.
Returns
true if there is success, false if there is an error

Definition at line 998 of file wg0x.cpp.

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

Definition at line 970 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
comused to perform communication with device
addressWG0X (FPGA) local bus address to read from
datapointer to buffer where read data can be stored, must be at least length in size
lengthamount of data to read, limited at 511 bytes.
Returns
returns zero for success, non-zero for failure

Definition at line 1101 of file wg0x.cpp.

bool WG0X::readMotorHeatingModelParametersFromEeprom ( EthercatCom com,
MotorHeatingModelParametersEepromConfig config 
)

Reads actuator info from eeprom.

Parameters
comEtherCAT communication class used for communicating with device
acuator_infoStructure where actuator info will be stored.
Returns
true if there is success, false if there is an error

Definition at line 1017 of file wg0x.cpp.

string WG0X::safetyDisableString ( uint8_t  status)
staticprotected

Definition at line 1168 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 695 of file wg0x.cpp.

bool WG0X::timestamp_jump ( uint32_t  timestamp,
uint32_t  last_timestamp,
uint32_t  amount 
)
staticprotected

Definition at line 742 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 684 of file wg0x.cpp.

bool WG0X::tryLockWG0XDiagnostics ( )
protected

Definition at line 1118 of file wg0x.cpp.

void WG0X::unlockWG0XDiagnostics ( )
protected

Definition at line 1133 of file wg0x.cpp.

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

Reimplemented from EthercatDevice.

Definition at line 613 of file wg0x.cpp.

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

Definition at line 664 of file wg0x.cpp.

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

Definition at line 748 of file wg0x.cpp.

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

Definition at line 959 of file wg0x.cpp.

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
comused to perform communication with device
addressWG0X (FPGA) local bus address to write data to
datapointer to buffer where write data is stored, must be at least length in size
lengthamount of data to write, limited at 507 bytes
Returns
returns zero for success, non-zero for failure

Definition at line 1155 of file wg0x.cpp.

Member Data Documentation

enum { ... } WG0X::__attribute__
pr2_hardware_interface::Actuator WG0X::actuator_
protected

Definition at line 270 of file wg0x.h.

WG0XActuatorInfo WG0X::actuator_info_
protected

Definition at line 263 of file wg0x.h.

ethercat_hardware::ActuatorInfo WG0X::actuator_info_msg_
protected

Definition at line 267 of file wg0x.h.

const unsigned WG0X::ACTUATOR_INFO_PAGE = 4095
staticprotected

Definition at line 383 of file wg0x.h.

AppRamStatus WG0X::app_ram_status_
protected

Definition at line 324 of file wg0x.h.

uint8_t WG0X::board_major_
protected

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

Definition at line 260 of file wg0x.h.

uint8_t WG0X::board_minor_
protected

Printed circuit assembly revision.

Definition at line 261 of file wg0x.h.

double WG0X::cached_zero_offset_
protected

Definition at line 305 of file wg0x.h.

int WG0X::calibration_status_
protected

Definition at line 307 of file wg0x.h.

const unsigned WG0X::COMMAND_PHY_ADDR = 0x1000
staticprotected

Definition at line 356 of file wg0x.h.

WG0XConfigInfo WG0X::config_info_
protected

Definition at line 264 of file wg0x.h.

int WG0X::consecutive_drops_
protected

Definition at line 399 of file wg0x.h.

pr2_hardware_interface::DigitalOut WG0X::digital_out_
protected

Definition at line 271 of file wg0x.h.

bool WG0X::disable_motor_model_checking_
protected

Definition at line 387 of file wg0x.h.

int WG0X::drops_
protected

Definition at line 398 of file wg0x.h.

ethercat_hardware::WGEeprom WG0X::eeprom_
protected

Access to device eeprom.

Definition at line 354 of file wg0x.h.

bool WG0X::encoder_errors_detected_
protected

Definition at line 301 of file wg0x.h.

bool WG0X::fpga_internal_reset_detected_
protected

Definition at line 300 of file wg0x.h.

uint8_t WG0X::fw_major_
protected

Definition at line 258 of file wg0x.h.

uint8_t WG0X::fw_minor_
protected

Definition at line 259 of file wg0x.h.

bool WG0X::has_error_
protected

Definition at line 295 of file wg0x.h.

bool WG0X::in_lockout_
protected

Definition at line 293 of file wg0x.h.

uint32_t WG0X::last_last_timestamp_
protected

Definition at line 397 of file wg0x.h.

uint32_t WG0X::last_timestamp_
protected

Definition at line 396 of file wg0x.h.

ethercat_hardware::WGMailbox WG0X::mailbox_
protected

Mailbox access to device.

Definition at line 351 of file wg0x.h.

uint16_t WG0X::max_board_temperature_
protected

Definition at line 296 of file wg0x.h.

uint16_t WG0X::max_bridge_temperature_
protected

Definition at line 296 of file wg0x.h.

int WG0X::max_consecutive_drops_
protected

Definition at line 400 of file wg0x.h.

double WG0X::max_current_
protected

min(board current limit, actuator current limit)

Definition at line 265 of file wg0x.h.

boost::shared_ptr<ethercat_hardware::MotorHeatingModel> WG0X::motor_heating_model_
protected

Definition at line 393 of file wg0x.h.

boost::shared_ptr< ethercat_hardware::MotorHeatingModelCommon > WG0X::motor_heating_model_common_
staticprotected

Definition at line 392 of file wg0x.h.

MotorModel* WG0X::motor_model_
protected

Definition at line 386 of file wg0x.h.

ethercat_hardware::MotorTraceSample WG0X::motor_trace_sample_
protected

Definition at line 388 of file wg0x.h.

const unsigned WG0X::PDO_COMMAND_SYNCMAN_NUM = 0
staticprotected

Definition at line 359 of file wg0x.h.

const unsigned WG0X::PDO_STATUS_SYNCMAN_NUM = 1
staticprotected

Definition at line 360 of file wg0x.h.

pr2_hardware_interface::DigitalOut WG0X::publish_motor_trace_
protected

Definition at line 389 of file wg0x.h.

const int WG0X::PWM_MAX = 0x4000
staticprotected

Definition at line 347 of file wg0x.h.

bool WG0X::resetting_
protected

Definition at line 294 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 314 of file wg0x.h.

bool WG0X::status_checksum_error_
protected

Definition at line 298 of file wg0x.h.

const unsigned WG0X::STATUS_PHY_ADDR = 0x2000
staticprotected

Definition at line 357 of file wg0x.h.

bool WG0X::timestamp_jump_detected_
protected

Definition at line 299 of file wg0x.h.

bool WG0X::too_many_dropped_packets_
protected

Definition at line 297 of file wg0x.h.

WG0XDiagnostics WG0X::wg0x_collect_diagnostics_
protected

Definition at line 407 of file wg0x.h.

pthread_mutex_t WG0X::wg0x_diagnostics_lock_
protected

Definition at line 405 of file wg0x.h.

WG0XDiagnostics WG0X::wg0x_publish_diagnostics_
protected

Definition at line 406 of file wg0x.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:30