44 #include <dll/ethercat_dll.h>    45 #include <al/ethercat_AL.h>    46 #include <dll/ethercat_device_addressed_telegram.h>    47 #include <dll/ethercat_frame.h>    49 #include <boost/static_assert.hpp>    57   has_accel_and_ft_(false),
    58   pressure_checksum_error_(false),
    59   pressure_checksum_error_count_(0),
    60   accelerometer_samples_(0), 
    61   accelerometer_missed_samples_(0),
    63   last_pressure_time_(0),
    64   pressure_publisher_(NULL),
    65   accel_publisher_(NULL),
    66   ft_overload_limit_(31100),
    67   ft_overload_flags_(0),
    68   ft_disconnected_(false),
    69   ft_vhalf_error_(false),
    70   ft_sampling_rate_error_(false),
    72   ft_missed_samples_(0),
    73   diag_last_ft_sample_count_(0),
    74   raw_ft_publisher_(NULL),
    76   enable_pressure_sensor_(true),
    77   enable_ft_sensor_(false),
    78   enable_soft_processor_access_(true)
   103   unsigned int base_status_size = 
sizeof(
WG0XStatus);
   138   EtherCAT_FMMU_Config *fmmu = 
new EtherCAT_FMMU_Config(3);
   140   (*fmmu)[0] = EC_FMMU(start_address, 
   153   (*fmmu)[1] = EC_FMMU(start_address, 
   163   start_address += base_status_size;
   165   (*fmmu)[2] = EC_FMMU(start_address, 
   177   sh->set_fmmu_config(fmmu);
   179   EtherCAT_PD_Config *pd = 
new EtherCAT_PD_Config(5);
   183   (*pd)[0].ChannelEnable = 
true;
   184   (*pd)[0].ALEventEnable = 
true;
   187   (*pd)[1].ChannelEnable = 
true;
   189   (*pd)[2] = EC_SyncMan(WGMailbox::MBX_COMMAND_PHY_ADDR, WGMailbox::MBX_COMMAND_SIZE, EC_QUEUED, EC_WRITTEN_FROM_MASTER);
   190   (*pd)[2].ChannelEnable = 
true;
   191   (*pd)[2].ALEventEnable = 
true;
   193   (*pd)[3] = EC_SyncMan(WGMailbox::MBX_STATUS_PHY_ADDR, WGMailbox::MBX_STATUS_SIZE, EC_QUEUED);
   194   (*pd)[3].ChannelEnable = 
true;
   197   (*pd)[4].ChannelEnable = 
true;
   199   sh->set_pd_config(pd);
   214     bool poor_measured_motor_voltage = 
false;
   215     double max_pwm_ratio = double(0x2700) / double(
PWM_MAX);
   216     double board_resistance = 5.0;
   219       ROS_FATAL(
"Initializing motor trace failed");
   238       ROS_WARN(
"Gripper firmware version %d does not support enabling force/torque sensor", 
fw_major_);
   245       static const uint8_t PRESSURE_ENABLE_FLAG = 0x1;
   246       static const uint8_t FT_ENABLE_FLAG       = 0x2;
   247       static const unsigned PRESSURE_FT_ENABLE_ADDR = 0xAA;
   248       uint8_t pressure_ft_enable = 0;
   252       if (
writeMailbox(&com, PRESSURE_FT_ENABLE_ADDR, &pressure_ft_enable, 1) != 0)
   254         ROS_FATAL(
"Could not enable/disable pressure and force/torque sensors");
   303   string topic = 
"pressure";
   309   for (
int i = 0; i < 2; ++i) 
   326   string topic = 
"accelerometer";
   337     ROS_FATAL(
"An accelerometer of the name '%s' already exists.  Device #%02d has a duplicate name", 
accelerometer_.
name_.c_str(), 
sh_->get_ring_position());
   349     ROS_FATAL(
"An analog in of the name '%s' already exists.  Device #%02d has a duplicate name",
   361   std::string topic = 
"raw_ft";
   367     ROS_FATAL(
"Could not allocate raw_ft publisher");
   392         ROS_FATAL(
"Could not allocate ft publisher");
   400         ROS_FATAL(
"A force/torque sensor of the name '%s' already exists.  Device #%02d has a duplicate name", 
force_torque_.
name_.c_str(), 
sh_->get_ring_position());
   470   unsigned char *pressure_buf = (this_buffer + 
command_size_ + status_bytes);
   535       std::stringstream ss;
   536       ss << 
"Pressure buffer checksum error : " << std::endl;
   539         ss << std::uppercase << std::hex << std::setw(2) << std::setfill(
'0')
   540            << unsigned(pressure_buf[ii]) << 
" ";
   541         if ((ii%8) == 7) ss << std::endl;
   544       std::cerr << ss.str() << std::endl;
   552     for (
int i = 0; i < 22; ++i ) {
   568         for (
int i = 0; i < 22; ++i ) {
   595   count = 
min(4, count);
   598   for (
int i = 0; i < count; ++i)
   600     int32_t acc = status->
accel_[count - i - 1];
   601     int range = (acc >> 30) & 3;
   602     float d = 1 << (8 - range);
   613     for (
int i = 0; i < count; ++i)
   652   for (
unsigned i=0; i<6; ++i)
   654     int raw_data = sample.
data_[i];
   669     if ((sample.
vhalf_ == 0x0000) || (sample.
vhalf_ == 0xFFFF))
   683   for (
unsigned i=0; i<6; ++i)
   686     for (
unsigned j=0; j<6; ++j)
   693   wrench.force.x  = out[0];
   694   wrench.force.y  = out[1];
   695   wrench.force.z  = out[2];
   696   wrench.torque.x = out[3];
   697   wrench.torque.y = out[4];
   698   wrench.torque.z = out[5];
   717     for (
unsigned i=0; i<6; ++i)
   719       int raw_data = sample.
data_[i];
   726   int missed_samples = std::max(
int(0), 
int(new_samples) - 
int(
MAX_FT_SAMPLES));
   731   if (usable_samples == 0)
   737   ft_state.
samples_.resize(usable_samples);
   748   for (
unsigned sample_index=0; sample_index<usable_samples; ++sample_index)
   752     unsigned status_sample_index = usable_samples-sample_index-1;
   754     geometry_msgs::Wrench &wrench(ft_state.
samples_[sample_index]);
   759   if (usable_samples > 0)
   761     const geometry_msgs::Wrench &wrench(ft_state.
samples_[usable_samples-1]);
   776     for (
unsigned sample_num=0; sample_num<usable_samples; ++sample_num)
   780       ethercat_hardware::RawFTDataSample &msg_sample(
raw_ft_publisher_->
msg_.samples[usable_samples-sample_num-1]);
   785         msg_sample.data[ch_num] = sample.
data_[ch_num];
   787       msg_sample.vhalf = sample.
vhalf_;
   838   d.hardware_id = serial;
   845   const char * range_str = 
   846     (acmd.
range_ == 0) ? 
"+/-2G" :
   847     (acmd.
range_ == 1) ? 
"+/-4G" :
   848     (acmd.
range_ == 2) ? 
"+/-8G" :
   851   const char * bandwidth_str = 
   863   double sample_frequency = 0.0;
   869       if (((sample_frequency < 2000) || (sample_frequency > 4000)) && has_accelerometer)
   871         d.
mergeSummary(d.WARN, 
"Bad accelerometer sampling frequency");
   878   d.
addf(
"Accelerometer range", 
"%s (%d)", range_str, acmd.
range_);
   879   d.
addf(
"Accelerometer bandwidth", 
"%s (%d)", bandwidth_str, acmd.
bandwidth_);
   880   d.
addf(
"Accelerometer sample frequency", 
"%f", sample_frequency);
   904   d.hardware_id = serial;
   913     d.
summary(d.OK, 
"Pressure sensor disabled by user");
   918     d.
mergeSummary(d.ERROR, 
"Checksum error on pressure data");
   924     unsigned l_finger_good_count = 0;
   925     unsigned r_finger_good_count = 0;
   930       if ((l_data != 0xFFFF) && (l_data != 0x0000))
   932         ++l_finger_good_count;
   936       if ((r_data != 0xFFFF) && (r_data != 0x0000))
   938         ++r_finger_good_count;
   945     if ((l_finger_good_count == 0) && (r_finger_good_count == 0))
   947       d.
mergeSummary(d.WARN, 
"Pressure sensors may not be connected");
   952       if (l_finger_good_count == 0)
   954         d.
mergeSummary(d.WARN, 
"Sensor on left finger may not be connected");
   956       else if (l_finger_good_count < NUM_PRESSURE_REGIONS)
   958         d.
mergeSummary(d.WARN, 
"Sensor on left finger may have damaged sensor regions");
   961       if (r_finger_good_count == 0)
   963         d.
mergeSummary(d.WARN, 
"Sensor on right finger may not be connected");
   965       else if (r_finger_good_count < NUM_PRESSURE_REGIONS)
   967         d.
mergeSummary(d.WARN, 
"Sensor on right finger may have damaged sensor regions");
   976       std::stringstream ss;
   980         ss << std::uppercase << std::hex << std::setw(4) << std::setfill(
'0') 
   982         if (region_num%8 == 7) 
   985       d.
add(
"Right finger data",  ss.str());
   991         ss << std::uppercase << std::hex << std::setw(4) << std::setfill(
'0') 
   993         if (region_num%8 == 7) ss << std::endl;      
   995       d.
add(
"Left finger data",  ss.str());
  1009   d.hardware_id = serial;
  1015   double sample_frequency = 0.0;
  1023   d.
addf(
"F/T sample frequency", 
"%.2f (Hz)", sample_frequency);
  1025   std::stringstream ss;
  1029     ss.str(
""); ss << 
"Ch"<< (i);
  1030     d.
addf(ss.str(), 
"%d", int(sample.
data_[i]));
  1032   d.
addf(
"FT Vhalf", 
"%d", 
int(sample.
vhalf_));
  1040       ss << 
"Ch" << i << 
" ";
  1047   d.
add(
"Overload Channels", ss.str());
  1060     d.
mergeSummary(d.ERROR, 
"Vhalf error, amplifier circuity may be damaged"); 
  1064   if (ft_data.size() == 6)
  1066     d.
addf(
"Force X",  
"%f", ft_data[0]);
  1067     d.
addf(
"Force Y",  
"%f", ft_data[1]);
  1068     d.
addf(
"Force Z",  
"%f", ft_data[2]);
  1069     d.
addf(
"Torque X", 
"%f", ft_data[3]);
  1070     d.
addf(
"Torque Y", 
"%f", ft_data[4]);
  1071     d.
addf(
"Torque Z", 
"%f", ft_data[5]);
  1082   for (
int i=0; i<6; ++i)
  1086     for (
int j=0; j<6; ++j)
  1088       calibration_coeff(i,j) = (i==j) ? 1.0 : 0.0;
  1096   for (
int i=0; i<6; ++i)
  1098     ROS_INFO(
"offset[%d] = %f", i, offset(i));
  1100   for (
int i=0; i<6; ++i)
  1102     ROS_INFO(
"gain[%d] = %f", i, gain(i));
  1104   for (
int i=0; i<6; ++i)
  1106     ROS_INFO(
"coeff[%d] = [%f,%f,%f,%f,%f,%f]", i, 
  1107              calibration_coeff(i,0), calibration_coeff(i,1), 
  1108              calibration_coeff(i,2), calibration_coeff(i,3), 
  1109              calibration_coeff(i,4), calibration_coeff(i,5)
  1119     ROS_ERROR(
"Expected ft_param to have '%s' element", name);
  1126     ROS_ERROR(
"Expected FT param '%s' to be list type", name);
  1129   if (values.
size() != int(len))
  1131     ROS_ERROR(
"Expected FT param '%s' to have %d elements", name, len);
  1134   for (
unsigned i=0; i<len; ++i)
  1138       ROS_ERROR(
"Expected FT param %s[%d] to be floating point type", name, i);
  1141       results[i] = 
static_cast<double>(values[i]);
  1162     ROS_WARN(
"'ft_params' not available for force/torque sensor in namespace '%s'",
  1171     ROS_ERROR(
"expected ft_params to be struct type");
  1175   if (!getDoubleArray(params, 
"offsets", offsets_, 6))
  1180   if (!getDoubleArray(params, 
"gains", gains_, 6))
  1188     ROS_ERROR(
"Expected FT param 'calibration_coeff' to be list type");
  1191   if (coeff_matrix.
size() != 6)
  1193     ROS_ERROR(
"Expected FT param 'calibration_coeff' to have 6 elements");
  1197   for (
int i=0; i<6; ++i)
  1202       ROS_ERROR(
"Expected FT param calibration_coeff[%d] to be list type", i);
  1205     if (coeff_row.
size() != 6)
  1207       ROS_ERROR(
"Expected FT param calibration_coeff[%d] to have 6 elements", i);
  1211     for (
int j=0; j<6; ++j)
  1215         ROS_ERROR(
"Expected FT param calibration_coeff[%d,%d] to be floating point type", i,j);
  1218         calibration_coeff(i,j) = 
static_cast<double>(coeff_row[j]);
 
void add(WGMailbox *mbx, const std::string &actuator_name, const std::string &processor_name, unsigned iram_address, unsigned ctrl_address)
 
realtime_tools::RealtimePublisher< geometry_msgs::WrenchStamped > * ft_publisher_
 
bool initialize(EthercatCom *com)
 
static const int FT_VHALF_IDEAL
Vhalf ADC measurement is ideally about (1<<16)/2. 
 
static const unsigned NUM_FT_CHANNELS
 
WGSoftProcessor soft_processor_
 
realtime_tools::RealtimePublisher< ethercat_hardware::RawFTData > * raw_ft_publisher_
Realtime Publisher of RAW F/T data. 
 
bool initializeSoftProcessor()
 
unsigned int command_size_
 
void packCommand(unsigned char *buffer, bool halt, bool reset)
 
void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device 
 
static const unsigned SIZE
 
bool unpackFT(WG06StatusWithAccelAndFT *status, WG06StatusWithAccelAndFT *last_status)
Unpack force/torque ADC samples from realtime data. 
 
const double & offset(unsigned ch_num) const 
 
FTDataSample ft_samples_[4]
 
unsigned pressure_size_
Size in bytes of pressure data region. 
 
int initialize(pr2_hardware_interface::HardwareInterface *, bool allow_unprogrammed=true)
 
void summary(unsigned char lvl, const std::string s)
 
const double & gain(unsigned ch_num) const 
 
bool pressure_checksum_error_
Set true where checksum error on pressure data is detected, cleared on reset. 
 
bool ft_vhalf_error_
error with Vhalf reference voltage 
 
ros::Time last_publish_time_
Time diagnostics was last published. 
 
unsigned computeChecksum(void const *data, unsigned length)
 
pr2_hardware_interface::PressureSensor pressure_sensors_[2]
 
bool getDoubleArray(XmlRpc::XmlRpcValue params, const char *name, double *results, unsigned len)
 
realtime_tools::RealtimePublisher< pr2_msgs::PressureState > * pressure_publisher_
 
bool addPressureSensor(PressureSensor *sensor)
 
pr2_hardware_interface::AnalogIn ft_analog_in_
Provides F/T data to controllers (deprecated, use pr2_hardware_interface::ForceTorque instead) ...
 
bool initializeAccel(pr2_hardware_interface::HardwareInterface *hw)
 
uint8_t board_major_
Printed circuit board revision (for this value 0=='A', 1=='B') 
 
bool addAccelerometer(Accelerometer *accelerometer)
 
int ft_overload_limit_
Limit on raw range of F/T input. 
 
diagnostic_updater::DiagnosticStatusWrapper diagnostic_status_
 
unsigned accelerometer_samples_
Number of accelerometer samples since last publish cycle. 
 
uint64_t ft_sample_count_
Counts number of ft sensor samples. 
 
bool getRosParams(ros::NodeHandle nh)
Grabs ft rosparams from a given node hande namespace. 
 
bool status_checksum_error_
 
bool enable_pressure_sensor_
 
Type const & getType() const 
 
static const unsigned STATUS_PHY_ADDR
 
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. 
 
unsigned pressure_checksum_error_count_
debugging 
 
pr2_hardware_interface::DigitalOut digital_out_
 
void addf(const std::string &key, const char *format,...)
 
static const unsigned SIZE
 
bool unpackAccel(WG06StatusWithAccel *status, WG06StatusWithAccel *last_status)
Unpack 3-axis accelerometer samples from realtime data. 
 
static const unsigned SIZE
 
static const unsigned SIZE
 
FTParamsInternal ft_params_
 
std::vector< double > state_
 
pr2_hardware_interface::ForceTorque force_torque_
Provides F/T data to controllers. 
 
bool unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
 
unsigned int rotateRight8(unsigned in)
 
const double & calibration_coeff(unsigned row, unsigned col) const 
 
bool unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
 
uint64_t ft_missed_samples_
Counts number of ft sensor samples that were missed. 
 
pr2_hardware_interface::AnalogIn ft_raw_analog_in_
 
static const unsigned BIG_PRESSURE_PHY_ADDR
 
bool ft_disconnected_
f/t sensor may be disconnected 
 
std::vector< geometry_msgs::Wrench > samples_
 
uint64_t diag_last_ft_sample_count_
F/T Sample count last time diagnostics was published. 
 
pr2_hardware_interface::Actuator actuator_
 
void diagnosticsFT(diagnostic_updater::DiagnosticStatusWrapper &d, WG06StatusWithAccelAndFT *status)
 
pr2_hardware_interface::Accelerometer accelerometer_
 
AccelerometerCommand command_
 
void diagnosticsAccel(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *buffer)
 
const std::string & getNamespace() const 
 
WG0XConfigInfo config_info_
 
void diagnosticsWG06(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *)
 
AccelerometerState state_
 
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *)
For EtherCAT device that only publish one EtherCAT Status message. If sub-class implements multiDiagn...
 
EtherCAT_SlaveHandler * sh_
 
bool initializePressure(pr2_hardware_interface::HardwareInterface *hw)
 
bool unpackPressure(unsigned char *pressure_buf)
Unpack pressure sensor samples from realtime data. 
 
bool addAnalogIn(AnalogIn *analog_in)
 
PLUGINLIB_EXPORT_CLASS(WG06, EthercatDevice)
 
void mergeSummary(unsigned char lvl, const std::string s)
 
AppRamStatus app_ram_status_
 
int writeMailbox(EthercatCom *com, unsigned address, void const *data, unsigned length)
Write data to WG0X local bus using mailbox communication. 
 
void packCommand(unsigned char *buffer, bool halt, bool reset)
 
bool hasMember(const std::string &name) const 
 
PressureSensorState state_
 
void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device 
 
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) ...
 
uint32_t device_serial_number_
 
bool has_accel_and_ft_
True if device has accelerometer and force/torque sensor. 
 
std::vector< uint16_t > data_
 
unsigned int status_size_
 
realtime_tools::RealtimePublisher< pr2_msgs::AccelerometerState > * accel_publisher_
 
static const unsigned SIZE
 
bool verifyChecksum(const void *buffer, unsigned size)
 
bool getParam(const std::string &key, std::string &s) const 
 
static const unsigned PRESSURE_PHY_ADDR
 
uint8_t ft_overload_flags_
Bits 0-5 set to true if raw FT input goes beyond limit. 
 
ethercat_hardware::WGMailbox mailbox_
Mailbox access to device. 
 
static const int FT_VHALF_RANGE
allow vhalf to range +/- 300 from ideal 
 
static const unsigned COMMAND_PHY_ADDR
 
bool initializeFT(pr2_hardware_interface::HardwareInterface *hw)
 
void add(const std::string &key, const T &val)
 
bool hasParam(const std::string &key) const 
 
#define ROS_ERROR_STREAM(args)
 
static const unsigned NUM_PRESSURE_REGIONS
 
static const unsigned MAX_FT_SAMPLES
 
static double min(double a, double b)
 
bool enable_soft_processor_access_
 
DigitalOutCommand command_
 
bool ft_sampling_rate_error_
True if FT sampling rate was incorrect. 
 
uint16_t r_finger_tip_[22]
 
void convertFTDataSampleToWrench(const FTDataSample &sample, geometry_msgs::Wrench &wrench)
Convert FTDataSample to Wrench using gain, offset, and coefficient matrix. 
 
uint16_t l_finger_tip_[22]
 
bool addForceTorque(ForceTorque *forcetorque)
 
virtual int initialize(pr2_hardware_interface::HardwareInterface *, bool allow_unprogrammed=true)
 
void diagnosticsPressure(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *buffer)
 
ForceTorqueCommand command_
 
std::vector< geometry_msgs::Vector3 > samples_
 
uint32_t last_pressure_time_
 
WG0XActuatorInfo actuator_info_