Public Types |
enum | { PRODUCT_CODE = 6805006
} |
Public Member Functions |
void | construct (EtherCAT_SlaveHandler *sh, int &start_address) |
| < Construct EtherCAT device
|
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.
|
void | packCommand (unsigned char *buffer, bool halt, bool reset) |
bool | unpackState (unsigned char *this_buffer, unsigned char *prev_buffer) |
| WG06 () |
| ~WG06 () |
Private Member Functions |
void | convertFTDataSampleToWrench (const FTDataSample &sample, geometry_msgs::Wrench &wrench) |
| Convert FTDataSample to Wrench using gain, offset, and coefficient matrix.
|
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.
|
bool | unpackFT (WG06StatusWithAccelAndFT *status, WG06StatusWithAccelAndFT *last_status) |
| Unpack force/torque ADC samples from realtime data.
|
bool | unpackPressure (unsigned char *pressure_buf) |
| Unpack pressure sensor samples from realtime data.
|
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.
|
unsigned | accelerometer_samples_ |
| Number of accelerometer samples since last publish cycle.
|
uint64_t | diag_last_ft_sample_count_ |
| F/T Sample count last time diagnostics was published.
|
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.
|
pr2_hardware_interface::AnalogIn | ft_analog_in_ |
| Provides F/T data to controllers (deprecated, use pr2_hardware_interface::ForceTorque instead)
|
bool | ft_disconnected_ |
| f/t sensor may be disconnected
|
uint64_t | ft_missed_samples_ |
| Counts number of ft sensor samples that were missed.
|
uint8_t | ft_overload_flags_ |
| Bits 0-5 set to true if raw FT input goes beyond limit.
|
int | ft_overload_limit_ |
| Limit on raw range of F/T input.
|
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.
|
bool | ft_sampling_rate_error_ |
| True if FT sampling rate was incorrect.
|
bool | ft_vhalf_error_ |
| error with Vhalf reference voltage
|
bool | has_accel_and_ft_ |
| True if device has accelerometer and force/torque sensor.
|
uint32_t | last_pressure_time_ |
ros::Time | last_publish_time_ |
| Time diagnostics was last published.
|
bool | pressure_checksum_error_ |
| Set true where checksum error on pressure data is detected, cleared on reset.
|
unsigned | pressure_checksum_error_count_ |
| debugging
|
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.
|
realtime_tools::RealtimePublisher
< ethercat_hardware::RawFTData > * | raw_ft_publisher_ |
| Realtime Publisher of RAW F/T data.
|
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.
|
static const int | FT_VHALF_RANGE = 300 |
| allow vhalf to range +/- 300 from ideal
|
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 |
Definition at line 163 of file wg06.h.
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 635 of file wg06.cpp.