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 | diagnosticsAccel (diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *buffer) |
| void | diagnosticsFT (diagnostic_updater::DiagnosticStatusWrapper &d, WG06StatusWithAccelAndFT *status) |
| void | diagnosticsWG06 (diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *) |
| 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 (WG06Pressure *p) |
| | 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 | first_publish_ |
| pr2_hardware_interface::AnalogIn | ft_analog_in_ |
| uint64_t | ft_missed_samples_ |
| | Counts number of ft sensor samples that were missed.
|
| FTParamsInternal | ft_params_ |
realtime_tools::RealtimePublisher
< geometry_msgs::Wrench > * | ft_publisher_ |
| pr2_hardware_interface::AnalogIn | ft_raw_analog_in_ |
| | Provides raw F/T data to controllers.
|
| uint64_t | ft_sample_count_ |
| | Counts number of ft sensor samples.
|
| 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.
|
realtime_tools::RealtimePublisher
< pr2_msgs::PressureState > * | pressure_publisher_ |
| pr2_hardware_interface::PressureSensor | pressure_sensors_ [2] |
realtime_tools::RealtimePublisher
< ethercat_hardware::RawFTData > * | raw_ft_publisher_ |
| | Realtime Publisher of RAW F/T data.
|
Static Private Attributes |
| static const unsigned | MAX_FT_SAMPLES = 4 |
| static const unsigned | NUM_FT_CHANNELS = 6 |
| static const unsigned | PRESSURE_PHY_ADDR = 0x2200 |