Public Types | Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
WG06 Class Reference

#include <wg06.h>

Inheritance diagram for WG06:
Inheritance graph
[legend]

Public Types

enum  { PRODUCT_CODE = 6805006 }
 
- 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...
 
int initialize (pr2_hardware_interface::HardwareInterface *, bool allow_unprogrammed=true)
 
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...
 
void packCommand (unsigned char *buffer, bool halt, bool reset)
 
bool unpackState (unsigned char *this_buffer, unsigned char *prev_buffer)
 
 WG06 ()
 
 ~WG06 ()
 
- Public Member Functions inherited from WG0X
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...
 
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...
 
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 ()
 

Private Member Functions

void convertFTDataSampleToWrench (const FTDataSample &sample, geometry_msgs::Wrench &wrench)
 Convert FTDataSample to Wrench using gain, offset, and coefficient matrix. More...
 
void diagnosticsAccel (diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *buffer)
 
void diagnosticsFT (diagnostic_updater::DiagnosticStatusWrapper &d, WG06StatusWithAccelAndFT *status)
 
void diagnosticsPressure (diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *buffer)
 
void diagnosticsWG06 (diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *)
 
bool initializeAccel (pr2_hardware_interface::HardwareInterface *hw)
 
bool initializeFT (pr2_hardware_interface::HardwareInterface *hw)
 
bool initializePressure (pr2_hardware_interface::HardwareInterface *hw)
 
bool initializeSoftProcessor ()
 
bool unpackAccel (WG06StatusWithAccel *status, WG06StatusWithAccel *last_status)
 Unpack 3-axis accelerometer samples from realtime data. More...
 
bool unpackFT (WG06StatusWithAccelAndFT *status, WG06StatusWithAccelAndFT *last_status)
 Unpack force/torque ADC samples from realtime data. More...
 
bool unpackPressure (unsigned char *pressure_buf)
 Unpack pressure sensor samples from realtime data. More...
 

Private Attributes

realtime_tools::RealtimePublisher< pr2_msgs::AccelerometerState > * accel_publisher_
 
pr2_hardware_interface::Accelerometer accelerometer_
 
unsigned accelerometer_missed_samples_
 Total of accelerometer samples that were missed. More...
 
unsigned accelerometer_samples_
 Number of accelerometer samples since last publish cycle. More...
 
uint64_t diag_last_ft_sample_count_
 F/T Sample count last time diagnostics was published. More...
 
bool enable_ft_sensor_
 
bool enable_pressure_sensor_
 
bool enable_soft_processor_access_
 
bool first_publish_
 
pr2_hardware_interface::ForceTorque force_torque_
 Provides F/T data to controllers. More...
 
pr2_hardware_interface::AnalogIn ft_analog_in_
 Provides F/T data to controllers (deprecated, use pr2_hardware_interface::ForceTorque instead) More...
 
bool ft_disconnected_
 f/t sensor may be disconnected More...
 
uint64_t ft_missed_samples_
 Counts number of ft sensor samples that were missed. More...
 
uint8_t ft_overload_flags_
 Bits 0-5 set to true if raw FT input goes beyond limit. More...
 
int ft_overload_limit_
 Limit on raw range of F/T input. More...
 
FTParamsInternal ft_params_
 
realtime_tools::RealtimePublisher< geometry_msgs::WrenchStamped > * ft_publisher_
 
pr2_hardware_interface::AnalogIn ft_raw_analog_in_
 
uint64_t ft_sample_count_
 Counts number of ft sensor samples. More...
 
bool ft_sampling_rate_error_
 True if FT sampling rate was incorrect. More...
 
bool ft_vhalf_error_
 error with Vhalf reference voltage More...
 
bool has_accel_and_ft_
 True if device has accelerometer and force/torque sensor. More...
 
uint32_t last_pressure_time_
 
ros::Time last_publish_time_
 Time diagnostics was last published. More...
 
bool pressure_checksum_error_
 Set true where checksum error on pressure data is detected, cleared on reset. More...
 
unsigned pressure_checksum_error_count_
 debugging More...
 
realtime_tools::RealtimePublisher< pr2_msgs::PressureState > * pressure_publisher_
 
pr2_hardware_interface::PressureSensor pressure_sensors_ [2]
 
unsigned pressure_size_
 Size in bytes of pressure data region. More...
 
realtime_tools::RealtimePublisher< ethercat_hardware::RawFTData > * raw_ft_publisher_
 Realtime Publisher of RAW F/T data. More...
 
WGSoftProcessor soft_processor_
 

Static Private Attributes

static const unsigned BIG_PRESSURE_PHY_ADDR = 0x2600
 
static const int FT_VHALF_IDEAL = 32768
 Vhalf ADC measurement is ideally about (1<<16)/2. More...
 
static const int FT_VHALF_RANGE = 300
 allow vhalf to range +/- 300 from ideal More...
 
static const unsigned MAX_FT_SAMPLES = 4
 
static const unsigned NUM_FT_CHANNELS = 6
 
static const unsigned NUM_PRESSURE_REGIONS = 22
 
static const unsigned PRESSURE_PHY_ADDR = 0x2200
 

Additional Inherited Members

- Static Public Member Functions inherited from WG0X
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...
 
- 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_
 
- Protected Types inherited from WG0X
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 inherited from WG0X
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 inherited from WG0X
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 inherited from WG0X
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 inherited from WG0X
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
 

Detailed Description

Definition at line 163 of file wg06.h.

Member Enumeration Documentation

anonymous enum
Enumerator
PRODUCT_CODE 

Definition at line 174 of file wg06.h.

Constructor & Destructor Documentation

WG06::WG06 ( )

Definition at line 56 of file wg06.cpp.

WG06::~WG06 ( )

Definition at line 84 of file wg06.cpp.

Member Function Documentation

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

< Construct EtherCAT device

Construct non-EtherCAT device

Reimplemented from EthercatDevice.

Definition at line 90 of file wg06.cpp.

void WG06::convertFTDataSampleToWrench ( const FTDataSample sample,
geometry_msgs::Wrench &  wrench 
)
private

Convert FTDataSample to Wrench using gain, offset, and coefficient matrix.

perform offset and gains multiplication on raw data and then multiply by calibration matrix to get force and torque values. The calibration matrix is based on "raw" deltaR/R values from strain gauges

Force/Torque = Coeff * ADCVoltage

Coeff = RawCoeff / ( ExcitationVoltage * AmplifierGain ) = RawCoeff / ( 2.5V * AmplifierGain )

ADCVoltage = Vref / 2^16 = 2.5 / 2^16

Force/Torque = RawCalibrationCoeff / ( ExcitationVoltage * AmplifierGain ) * (ADCValues * 2.5V/2^16) = (RawCalibration * ADCValues) / (AmplifierGain * 2^16)

Note on hardware circuit and Vref and excitation voltage should have save value. Thus, with Force/Torque calculation they cancel out.

Definition at line 646 of file wg06.cpp.

void WG06::diagnosticsAccel ( diagnostic_updater::DiagnosticStatusWrapper d,
unsigned char *  buffer 
)
private

Definition at line 831 of file wg06.cpp.

void WG06::diagnosticsFT ( diagnostic_updater::DiagnosticStatusWrapper d,
WG06StatusWithAccelAndFT status 
)
private

Definition at line 1002 of file wg06.cpp.

void WG06::diagnosticsPressure ( diagnostic_updater::DiagnosticStatusWrapper d,
unsigned char *  buffer 
)
private

Definition at line 891 of file wg06.cpp.

void WG06::diagnosticsWG06 ( diagnostic_updater::DiagnosticStatusWrapper d,
unsigned char *  buffer 
)
private

Definition at line 885 of file wg06.cpp.

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

Reimplemented from WG0X.

Definition at line 203 of file wg06.cpp.

bool WG06::initializeAccel ( pr2_hardware_interface::HardwareInterface hw)
private

Definition at line 324 of file wg06.cpp.

bool WG06::initializeFT ( pr2_hardware_interface::HardwareInterface hw)
private

Definition at line 344 of file wg06.cpp.

bool WG06::initializePressure ( pr2_hardware_interface::HardwareInterface hw)
private

Definition at line 300 of file wg06.cpp.

bool WG06::initializeSoftProcessor ( )
private

Definition at line 410 of file wg06.cpp.

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

Definition at line 808 of file wg06.cpp.

void WG06::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 431 of file wg06.cpp.

bool WG06::unpackAccel ( WG06StatusWithAccel status,
WG06StatusWithAccel last_status 
)
private

Unpack 3-axis accelerometer samples from realtime data.

Returns
True, if there are no problems.

Definition at line 587 of file wg06.cpp.

bool WG06::unpackFT ( WG06StatusWithAccelAndFT status,
WG06StatusWithAccelAndFT last_status 
)
private

Unpack force/torque ADC samples from realtime data.

Returns
True, if there are no problems, false if there is something wrong with the data.

Definition at line 707 of file wg06.cpp.

bool WG06::unpackPressure ( unsigned char *  pressure_buf)
private

Unpack pressure sensor samples from realtime data.

Returns
True, if there are no problems, false if there is something wrong with the data.

Definition at line 522 of file wg06.cpp.

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

Reimplemented from EthercatDevice.

Definition at line 461 of file wg06.cpp.

Member Data Documentation

realtime_tools::RealtimePublisher<pr2_msgs::AccelerometerState>* WG06::accel_publisher_
private

Definition at line 215 of file wg06.h.

pr2_hardware_interface::Accelerometer WG06::accelerometer_
private

Definition at line 184 of file wg06.h.

unsigned WG06::accelerometer_missed_samples_
private

Total of accelerometer samples that were missed.

Definition at line 208 of file wg06.h.

unsigned WG06::accelerometer_samples_
private

Number of accelerometer samples since last publish cycle.

Definition at line 207 of file wg06.h.

const unsigned WG06::BIG_PRESSURE_PHY_ADDR = 0x2600
staticprivate

Definition at line 181 of file wg06.h.

uint64_t WG06::diag_last_ft_sample_count_
private

F/T Sample count last time diagnostics was published.

Definition at line 229 of file wg06.h.

bool WG06::enable_ft_sensor_
private

Definition at line 243 of file wg06.h.

bool WG06::enable_pressure_sensor_
private

Definition at line 242 of file wg06.h.

bool WG06::enable_soft_processor_access_
private

Certain version of WG06 firmware (2.xx and 3.xx) use soft-processors to communicate with certain peripherals (pressure sensor, F/T sensor, accelerometer...) For purposes of supporting new types of devices, the soft-processor FW can be be modified through use of service calls.

Definition at line 250 of file wg06.h.

bool WG06::first_publish_
private

Definition at line 210 of file wg06.h.

pr2_hardware_interface::ForceTorque WG06::force_torque_
private

Provides F/T data to controllers.

Definition at line 234 of file wg06.h.

pr2_hardware_interface::AnalogIn WG06::ft_analog_in_
private

Provides F/T data to controllers (deprecated, use pr2_hardware_interface::ForceTorque instead)

Definition at line 232 of file wg06.h.

bool WG06::ft_disconnected_
private

f/t sensor may be disconnected

Definition at line 224 of file wg06.h.

uint64_t WG06::ft_missed_samples_
private

Counts number of ft sensor samples that were missed.

Definition at line 228 of file wg06.h.

uint8_t WG06::ft_overload_flags_
private

Bits 0-5 set to true if raw FT input goes beyond limit.

Definition at line 223 of file wg06.h.

int WG06::ft_overload_limit_
private

Limit on raw range of F/T input.

Definition at line 222 of file wg06.h.

FTParamsInternal WG06::ft_params_
private

Definition at line 240 of file wg06.h.

realtime_tools::RealtimePublisher<geometry_msgs::WrenchStamped>* WG06::ft_publisher_
private

Definition at line 238 of file wg06.h.

pr2_hardware_interface::AnalogIn WG06::ft_raw_analog_in_
private

Provides raw F/T data to controllers

Definition at line 230 of file wg06.h.

uint64_t WG06::ft_sample_count_
private

Counts number of ft sensor samples.

Definition at line 227 of file wg06.h.

bool WG06::ft_sampling_rate_error_
private

True if FT sampling rate was incorrect.

Definition at line 226 of file wg06.h.

bool WG06::ft_vhalf_error_
private

error with Vhalf reference voltage

Definition at line 225 of file wg06.h.

const int WG06::FT_VHALF_IDEAL = 32768
staticprivate

Vhalf ADC measurement is ideally about (1<<16)/2.

Definition at line 220 of file wg06.h.

const int WG06::FT_VHALF_RANGE = 300
staticprivate

allow vhalf to range +/- 300 from ideal

Definition at line 221 of file wg06.h.

bool WG06::has_accel_and_ft_
private

True if device has accelerometer and force/torque sensor.

Definition at line 201 of file wg06.h.

uint32_t WG06::last_pressure_time_
private

Definition at line 213 of file wg06.h.

ros::Time WG06::last_publish_time_
private

Time diagnostics was last published.

Definition at line 209 of file wg06.h.

const unsigned WG06::MAX_FT_SAMPLES = 4
staticprivate

Definition at line 218 of file wg06.h.

const unsigned WG06::NUM_FT_CHANNELS = 6
staticprivate

Definition at line 219 of file wg06.h.

const unsigned WG06::NUM_PRESSURE_REGIONS = 22
staticprivate

Definition at line 212 of file wg06.h.

bool WG06::pressure_checksum_error_
private

Set true where checksum error on pressure data is detected, cleared on reset.

Definition at line 203 of file wg06.h.

unsigned WG06::pressure_checksum_error_count_
private

debugging

Definition at line 204 of file wg06.h.

const unsigned WG06::PRESSURE_PHY_ADDR = 0x2200
staticprivate

Definition at line 180 of file wg06.h.

realtime_tools::RealtimePublisher<pr2_msgs::PressureState>* WG06::pressure_publisher_
private

Definition at line 214 of file wg06.h.

pr2_hardware_interface::PressureSensor WG06::pressure_sensors_[2]
private

Definition at line 183 of file wg06.h.

unsigned WG06::pressure_size_
private

Size in bytes of pressure data region.

Definition at line 205 of file wg06.h.

realtime_tools::RealtimePublisher<ethercat_hardware::RawFTData>* WG06::raw_ft_publisher_
private

Realtime Publisher of RAW F/T data.

Definition at line 237 of file wg06.h.

WGSoftProcessor WG06::soft_processor_
private

Definition at line 251 of file wg06.h.


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


ethercat_hardware
Author(s): Rob Wheeler , Derek King
autogenerated on Thu Mar 4 2021 03:10:21