Go to the documentation of this file.
35 #ifndef ETHERCAT_HARDWARE_WG06_H
36 #define ETHERCAT_HARDWARE_WG06_H
42 #include <pr2_msgs/PressureState.h>
43 #include <pr2_msgs/AccelerometerState.h>
44 #include <ethercat_hardware/RawFTData.h>
45 #include <geometry_msgs/WrenchStamped.h>
72 static const unsigned SIZE=61;
82 static const unsigned SIZE=16;
97 const double &
gain(
unsigned ch_num)
const {
return gains_[ch_num];}
138 static const unsigned SIZE=129;
158 static const unsigned SIZE=513;
169 void construct(EtherCAT_SlaveHandler *sh,
int &start_address);
170 void packCommand(
unsigned char *buffer,
bool halt,
bool reset);
171 bool unpackState(
unsigned char *this_buffer,
unsigned char *prev_buffer);
173 virtual void multiDiagnostics(vector<diagnostic_msgs::DiagnosticStatus> &vec,
unsigned char *buffer);
void diagnosticsPressure(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *buffer)
uint32_t last_pressure_time_
int initialize(pr2_hardware_interface::HardwareInterface *, bool allow_unprogrammed=true)
bool unpackPressure(unsigned char *pressure_buf)
Unpack pressure sensor samples from realtime data.
bool getRosParams(ros::NodeHandle nh)
Grabs ft rosparams from a given node hande namespace.
static const int FT_VHALF_IDEAL
Vhalf ADC measurement is ideally about (1<<16)/2.
bool pressure_checksum_error_
Set true where checksum error on pressure data is detected, cleared on reset.
realtime_tools::RealtimePublisher< ethercat_hardware::RawFTData > * raw_ft_publisher_
Realtime Publisher of RAW F/T data.
const double & gain(unsigned ch_num) const
bool unpackAccel(WG06StatusWithAccel *status, WG06StatusWithAccel *last_status)
Unpack 3-axis accelerometer samples from realtime data.
int16_t programmed_current_
static const unsigned SIZE
double & offset(unsigned ch_num)
int16_t programmed_pwm_value_
uint16_t r_finger_tip_[22]
unsigned pressure_size_
Size in bytes of pressure data region.
uint16_t l_finger_tip_[22]
int ft_overload_limit_
Limit on raw range of F/T input.
bool ft_vhalf_error_
error with Vhalf reference voltage
int16_t measured_current_
const double & offset(unsigned ch_num) const
FTParamsInternal ft_params_
bool unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
uint16_t board_temperature_
class FTParamsInternal __attribute__
uint16_t bridge_temperature_
static const unsigned SIZE
pr2_hardware_interface::ForceTorque force_torque_
Provides F/T data to controllers.
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 mult...
unsigned accelerometer_missed_samples_
Total of accelerometer samples that were missed.
realtime_tools::RealtimePublisher< pr2_msgs::AccelerometerState > * accel_publisher_
void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device
static const unsigned SIZE
pr2_hardware_interface::Accelerometer accelerometer_
static const unsigned SIZE
bool enable_pressure_sensor_
bool unpackFT(WG06StatusWithAccelAndFT *status, WG06StatusWithAccelAndFT *last_status)
Unpack force/torque ADC samples from realtime data.
void diagnosticsAccel(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *buffer)
unsigned pressure_checksum_error_count_
debugging
bool initializeFT(pr2_hardware_interface::HardwareInterface *hw)
uint64_t ft_missed_samples_
Counts number of ft sensor samples that were missed.
static const unsigned PRESSURE_PHY_ADDR
static const unsigned MAX_FT_SAMPLES
uint16_t num_encoder_errors_
pr2_hardware_interface::AnalogIn ft_raw_analog_in_
const double & calibration_coeff(unsigned row, unsigned col) const
static const unsigned BIG_PRESSURE_PHY_ADDR
void diagnosticsFT(diagnostic_updater::DiagnosticStatusWrapper &d, WG06StatusWithAccelAndFT *status)
void packCommand(unsigned char *buffer, bool halt, bool reset)
uint64_t diag_last_ft_sample_count_
F/T Sample count last time diagnostics was published.
uint64_t ft_sample_count_
Counts number of ft sensor samples.
int16_t programmed_current_
uint16_t num_encoder_errors_
void diagnosticsWG06(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *)
bool ft_sampling_rate_error_
True if FT sampling rate was incorrect.
void convertFTDataSampleToWrench(const FTDataSample &sample, geometry_msgs::Wrench &wrench)
Convert FTDataSample to Wrench using gain, offset, and coefficient matrix.
static const unsigned NUM_FT_CHANNELS
FTDataSample ft_samples_[4]
bool initializeAccel(pr2_hardware_interface::HardwareInterface *hw)
uint16_t bridge_temperature_
bool ft_disconnected_
f/t sensor may be disconnected
int16_t measured_current_
bool initializePressure(pr2_hardware_interface::HardwareInterface *hw)
int32_t encoder_index_pos_
pr2_hardware_interface::AnalogIn ft_analog_in_
Provides F/T data to controllers (deprecated, use pr2_hardware_interface::ForceTorque instead)
static const int FT_VHALF_RANGE
allow vhalf to range +/- 300 from ideal
static const unsigned SIZE
bool has_accel_and_ft_
True if device has accelerometer and force/torque sensor.
realtime_tools::RealtimePublisher< geometry_msgs::WrenchStamped > * ft_publisher_
WGSoftProcessor soft_processor_
int32_t encoder_index_pos_
ros::Time last_publish_time_
Time diagnostics was last published.
pr2_hardware_interface::PressureSensor pressure_sensors_[2]
static const unsigned NUM_PRESSURE_REGIONS
bool initializeSoftProcessor()
uint8_t ft_overload_flags_
Bits 0-5 set to true if raw FT input goes beyond limit.
realtime_tools::RealtimePublisher< pr2_msgs::PressureState > * pressure_publisher_
double calibration_coeff_[36]
unsigned accelerometer_samples_
Number of accelerometer samples since last publish cycle.
bool getDoubleArray(XmlRpc::XmlRpcValue params, const char *name, double *results, unsigned len)
int16_t programmed_pwm_value_
bool enable_soft_processor_access_
uint16_t board_temperature_
ethercat_hardware
Author(s): Rob Wheeler
, Derek King
autogenerated on Thu Sep 26 2024 02:44:04