sr06.cpp
Go to the documentation of this file.
1 
28 
30 
31 #include <math.h>
32 #include <sstream>
33 #include <string>
34 #include <vector>
35 #include <iomanip>
36 #include <boost/foreach.hpp>
37 #include <std_msgs/Int16.h>
38 #include <fcntl.h>
39 #include <stdio.h>
40 #include <pthread.h>
41 
42 #include <sr_utilities/sr_math_utils.hpp>
43 
44 using std::string;
45 using std::stringstream;
46 using std::vector;
47 
49 
50 #include <boost/static_assert.hpp>
51 
53 {
54 // check is the EDC_COMMAND is 32bits on the computer
55 // if not, fails
56  BOOST_STATIC_ASSERT(sizeof(EDC_COMMAND) == 4);
57 } // namespace is_edc_command_32_bits
58 
59 #define ETHERCAT_STATUS_DATA_SIZE sizeof(ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS)
60 #define ETHERCAT_COMMAND_DATA_SIZE sizeof(ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND)
61 
62 #define ETHERCAT_CAN_BRIDGE_DATA_SIZE sizeof(ETHERCAT_CAN_BRIDGE_DATA)
63 
64 #define ETHERCAT_COMMAND_DATA_ADDRESS PALM_0200_ETHERCAT_COMMAND_DATA_ADDRESS
65 #define ETHERCAT_STATUS_DATA_ADDRESS PALM_0200_ETHERCAT_STATUS_DATA_ADDRESS
66 #define ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS PALM_0200_ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS
67 #define ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS PALM_0200_ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS
68 
69 
70 PLUGINLIB_EXPORT_CLASS(SR06, EthercatDevice);
71 
79  : zero_buffer_read(0),
80  cycle_count(0)
81 {
82  /*
83  ROS_INFO("There are %d sensors", nb_sensors_const);
84  ROS_INFO( "device_pub_freq_const = %d", device_pub_freq_const );
85  ROS_INFO( "ros_pub_freq_const = %d", ros_pub_freq_const );
86  ROS_INFO( "max_iter_const = %d", max_iter_const );
87  ROS_INFO( "nb_sensors_const = %d", nb_sensors_const );
88  ROS_INFO("nb_publish_by_unpack_const = %d", nb_publish_by_unpack_const );
89  */
90 }
91 
125 void SR06::construct(EtherCAT_SlaveHandler *sh, int &start_address)
126 {
131 
132  ROS_INFO("Finished constructing the SR06 driver");
133 }
134 
138 int SR06::initialize(hardware_interface::HardwareInterface *hw, bool allow_unprogrammed)
139 {
140  int retval = SR0X::initialize(hw, allow_unprogrammed);
141 
142  if (retval != 0)
143  {
144  return retval;
145  }
146 
147  sr_hand_lib = boost::shared_ptr<shadow_robot::SrMotorHandLib<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS,
148  ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND> >(
149  new shadow_robot::SrMotorHandLib<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS,
150  ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND>(hw, nodehandle_, nh_tilde_,
152 
153  ROS_INFO("ETHERCAT_STATUS_DATA_SIZE = %4d bytes", static_cast<int> (ETHERCAT_STATUS_DATA_SIZE));
154  ROS_INFO("ETHERCAT_COMMAND_DATA_SIZE = %4d bytes", static_cast<int> (ETHERCAT_COMMAND_DATA_SIZE));
155  ROS_INFO("ETHERCAT_CAN_BRIDGE_DATA_SIZE = %4d bytes", static_cast<int> (ETHERCAT_CAN_BRIDGE_DATA_SIZE));
156 
157  // initialise the publisher for the extra analog inputs, gyroscope and accelerometer on the palm
159  new realtime_tools::RealtimePublisher<std_msgs::Float64MultiArray>(nodehandle_, "palm_extras", 10));
160 
161 
162  // Debug real time publisher: publishes the raw ethercat data
165  return retval;
166 }
167 
174 void SR06::multiDiagnostics(vector<diagnostic_msgs::DiagnosticStatus> &vec, unsigned char *buffer)
175 {
176  diagnostic_updater::DiagnosticStatusWrapper &d(diagnostic_status_);
177 
178  stringstream name;
179  string prefix = device_id_.empty() ? device_id_ : (device_id_ + " ");
180  d.name = prefix + "EtherCAT Dual CAN Palm";
181  d.summary(d.OK, "OK");
182  stringstream hwid;
183  hwid << sh_->get_product_code() << "-" << sh_->get_serial();
184  d.hardware_id = hwid.str();
185 
186  d.clear();
187  d.addf("Position", "%02d", sh_->get_ring_position());
188  d.addf("Product Code", "%d", sh_->get_product_code());
189  d.addf("Serial Number", "%d", sh_->get_serial());
190  d.addf("Revision", "%d", sh_->get_revision());
191  d.addf("Counter", "%d", ++counter_);
192 
193  d.addf("PIC idle time (in microsecs)", "%d", sr_hand_lib->main_pic_idle_time);
194  d.addf("Min PIC idle time (since last diagnostics)", "%d", sr_hand_lib->main_pic_idle_time_min);
195  // reset the idle time min to a big number, to get a fresh number on next diagnostic
196  sr_hand_lib->main_pic_idle_time_min = 1000;
197 
198  this->ethercatDiagnostics(d, 2);
199  vec.push_back(d);
200 
201  // Add the diagnostics from the hand
202  sr_hand_lib->add_diagnostics(vec, d);
203 
204  // Add the diagnostics from the tactiles
205  if (sr_hand_lib->tactiles != NULL)
206  {
207  sr_hand_lib->tactiles->add_diagnostics(vec, d);
208  }
209 }
210 
226 void SR06::packCommand(unsigned char *buffer, bool halt, bool reset)
227 {
228  SrEdc::packCommand(buffer, halt, reset);
229 
230  ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND *command =
231  reinterpret_cast<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND *>(buffer);
232  ETHERCAT_CAN_BRIDGE_DATA *message = reinterpret_cast<ETHERCAT_CAN_BRIDGE_DATA *>(buffer + ETHERCAT_COMMAND_DATA_SIZE);
233 
234  if (!flashing)
235  {
236  command->EDC_command = EDC_COMMAND_SENSOR_DATA;
237  }
238  else
239  {
240  command->EDC_command = EDC_COMMAND_CAN_DIRECT_MODE;
241  }
242 
243  // alternate between even and uneven motors
244  // and ask for the different informations.
245  sr_hand_lib->build_command(command);
246 
247  ROS_DEBUG("Sending command : Type : 0x%02X ; data : 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X "
248  "0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X",
249  command->to_motor_data_type,
250  command->motor_data[0],
251  command->motor_data[1],
252  command->motor_data[2],
253  command->motor_data[3],
254  command->motor_data[4],
255  command->motor_data[5],
256  command->motor_data[6],
257  command->motor_data[7],
258  command->motor_data[8],
259  command->motor_data[9],
260  command->motor_data[10],
261  command->motor_data[11],
262  command->motor_data[12],
263  command->motor_data[13],
264  command->motor_data[14],
265  command->motor_data[15],
266  command->motor_data[16],
267  command->motor_data[17],
268  command->motor_data[18],
269  command->motor_data[19]);
270 
271  build_CAN_message(message);
272 }
273 
292 bool SR06::unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
293 {
294  ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS *status_data =
295  reinterpret_cast<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS *>(this_buffer + command_size_);
296  ETHERCAT_CAN_BRIDGE_DATA *can_data = reinterpret_cast<ETHERCAT_CAN_BRIDGE_DATA *>(this_buffer + command_size_ +
298  // int16u *status_buffer = (int16u*)status_data;
299  static unsigned int num_rxed_packets = 0;
300 
301  ++num_rxed_packets;
302 
303 
304  // publishes the debug information (a slightly formatted version of the incoming ethercat packet):
305  if (debug_publisher->trylock())
306  {
307  debug_publisher->msg_.header.stamp = ros::Time::now();
308 
309  debug_publisher->msg_.sensors.clear();
310  for (unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
311  {
312  debug_publisher->msg_.sensors.push_back(status_data->sensors[i]);
313  }
314 
315  debug_publisher->msg_.motor_data_type.data = static_cast<int> (status_data->motor_data_type);
316  debug_publisher->msg_.which_motors = status_data->which_motors;
317  debug_publisher->msg_.which_motor_data_arrived = status_data->which_motor_data_arrived;
318  debug_publisher->msg_.which_motor_data_had_errors = status_data->which_motor_data_had_errors;
319 
320  debug_publisher->msg_.motor_data_packet_torque.clear();
321  debug_publisher->msg_.motor_data_packet_misc.clear();
322  for (unsigned int i = 0; i < 10; ++i)
323  {
324  debug_publisher->msg_.motor_data_packet_torque.push_back(status_data->motor_data_packet[i].torque);
325  debug_publisher->msg_.motor_data_packet_misc.push_back(status_data->motor_data_packet[i].misc);
326  }
327 
328  debug_publisher->msg_.tactile_data_type = static_cast<unsigned int>(
329  static_cast<int32u>(status_data->tactile_data_type));
330  debug_publisher->msg_.tactile_data_valid = static_cast<unsigned int> (
331  static_cast<int16u> (status_data->tactile_data_valid));
332  debug_publisher->msg_.tactile.clear();
333  for (unsigned int i = 0; i < 5; ++i)
334  {
335  debug_publisher->msg_.tactile.push_back(
336  static_cast<unsigned int> (static_cast<int16u> (status_data->tactile[i].word[0])));
337  }
338 
339  debug_publisher->msg_.idle_time_us = status_data->idle_time_us;
340 
341  debug_publisher->unlockAndPublish();
342  }
343 
344  if (status_data->EDC_command == EDC_COMMAND_INVALID)
345  {
346  // received empty message: the pic is not writing to its mailbox.
348  float percentage_packet_loss = 100.f * (static_cast<float>(zero_buffer_read) /
349  static_cast<float>(num_rxed_packets));
350 
351  ROS_DEBUG("Reception error detected : %d errors out of %d rxed packets (%2.3f%%) ; idle time %dus",
352  zero_buffer_read, num_rxed_packets, percentage_packet_loss, status_data->idle_time_us);
353  return true;
354  }
355 
356  // We received a coherent message.
357  // Update the library (positions, diagnostics values, actuators, etc...)
358  // with the received information
359  sr_hand_lib->update(status_data);
360 
361  // Now publish the additional data at 100Hz (every 10 cycles)
362  if (cycle_count >= 10)
363  {
364  // publish tactiles if we have them
365  if (sr_hand_lib->tactiles != NULL)
366  {
367  sr_hand_lib->tactiles->publish();
368  }
369 
370  // And we also publish the additional data (accelerometer / gyroscope / analog inputs)
371  std_msgs::Float64MultiArray extra_analog_msg;
372  extra_analog_msg.layout.dim.resize(3);
373  extra_analog_msg.data.resize(3 + 3 + 4);
374  std::vector<double> data;
375 
376  extra_analog_msg.layout.dim[0].label = "accelerometer";
377  extra_analog_msg.layout.dim[0].size = 3;
378  extra_analog_msg.data[0] = status_data->sensors[ACCX];
379  extra_analog_msg.data[1] = status_data->sensors[ACCY];
380  extra_analog_msg.data[2] = status_data->sensors[ACCZ];
381 
382  extra_analog_msg.layout.dim[1].label = "gyrometer";
383  extra_analog_msg.layout.dim[1].size = 3;
384  extra_analog_msg.data[3] = status_data->sensors[GYRX];
385  extra_analog_msg.data[4] = status_data->sensors[GYRY];
386  extra_analog_msg.data[5] = status_data->sensors[GYRZ];
387 
388  extra_analog_msg.layout.dim[2].label = "analog_inputs";
389  extra_analog_msg.layout.dim[2].size = 4;
390  extra_analog_msg.data[6] = status_data->sensors[ANA0];
391  extra_analog_msg.data[7] = status_data->sensors[ANA1];
392  extra_analog_msg.data[8] = status_data->sensors[ANA2];
393  extra_analog_msg.data[9] = status_data->sensors[ANA3];
394 
395  if (extra_analog_inputs_publisher->trylock())
396  {
397  extra_analog_inputs_publisher->msg_ = extra_analog_msg;
398  extra_analog_inputs_publisher->unlockAndPublish();
399  }
400 
401  cycle_count = 0;
402  }
403  ++cycle_count;
404 
405 
406  // If we're flashing, check is the packet has been acked
407  if (flashing & !can_packet_acked)
408  {
409  if (can_data_is_ack(can_data))
410  {
411  can_packet_acked = true;
412  }
413  }
414 
415  return true;
416 }
417 
419 {
420  // Reinitialize motors information
421  sr_hand_lib->reinitialize_motors();
422 }
423 
424 void SR06::get_board_id_and_can_bus(int board_id, int *can_bus, unsigned int *board_can_id)
425 {
426  // We're using 2 can busses,
427  // if motor id is between 0 and 9, then we're using the can_bus 1
428  // else, we're using the can bus 2.
429  int motor_id_tmp = board_id;
430  if (motor_id_tmp > 9)
431  {
432  motor_id_tmp -= 10;
433  *can_bus = 2;
434  }
435  else
436  {
437  *can_bus = 1;
438  }
439 
440  *board_can_id = motor_id_tmp;
441 }
442 
443 /* For the emacs weenies in the crowd.
444  Local Variables:
445  c-basic-offset: 2
446  End:
447 */
#define ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS
Definition: sr06.cpp:67
d
unsigned short int16u
virtual bool unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
This functions receives data from the EtherCAT bus.
Definition: sr06.cpp:292
ros::NodeHandle nh_tilde_
Definition: sr_edc.h:87
EDC_COMMAND_SENSOR_DATA
virtual int initialize(hardware_interface::HardwareInterface *hw, bool allow_unprogrammed=true)
Definition: sr0x.cpp:36
void summary(unsigned char lvl, const std::string s)
ANA0
ACCZ
virtual int initialize(hardware_interface::HardwareInterface *hw, bool allow_unprogrammed=true)
Definition: sr06.cpp:138
data
ACCX
#define ETHERCAT_STATUS_DATA_SIZE
Definition: sr06.cpp:59
This is a ROS driver for Shadow Robot #6 EtherCAT product ID.
unsigned int zero_buffer_read
Definition: sr06.h:95
ANA3
int counter_
Definition: sr_edc.h:85
void addf(const std::string &key, const char *format,...)
unsigned int int32u
#define ETHERCAT_COMMAND_DATA_ADDRESS
Definition: sr06.cpp:64
BOOST_STATIC_ASSERT(sizeof(EDC_COMMAND)==4)
EDC_COMMAND_CAN_DIRECT_MODE
virtual void multiDiagnostics(vector< diagnostic_msgs::DiagnosticStatus > &vec, unsigned char *buffer)
This function gives some diagnostics data.
Definition: sr06.cpp:174
virtual void construct(EtherCAT_SlaveHandler *sh, int &start_address, unsigned int ethercat_command_data_size, unsigned int ethercat_status_data_size, unsigned int ethercat_can_bridge_data_size, unsigned int ethercat_command_data_address, unsigned int ethercat_status_data_address, unsigned int ethercat_can_bridge_data_command_address, unsigned int ethercat_can_bridge_data_status_address)
Construct function, run at startup to set SyncManagers and FMMUs.
Definition: sr_edc.cpp:167
bool can_packet_acked
Definition: sr_edc.h:96
int16_t cycle_count
Definition: sr06.h:104
ANA2
ROSLIB_DECL std::string command(const std::string &cmd)
#define ROS_INFO(...)
ros::NodeHandle nodehandle_
Definition: sr_edc.h:86
ACCY
void build_CAN_message(ETHERCAT_CAN_BRIDGE_DATA *message)
Definition: sr_edc.cpp:615
PLUGINLIB_EXPORT_CLASS(SR06, EthercatDevice)
GYRY
EDC_COMMAND_INVALID
#define ETHERCAT_COMMAND_DATA_SIZE
Definition: sr06.cpp:60
bool can_data_is_ack(ETHERCAT_CAN_BRIDGE_DATA *packet)
This function checks if the can packet in the unpackState() this_buffer is an ACK.
Definition: sr_edc.cpp:668
#define ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS
Definition: sr06.cpp:66
boost::shared_ptr< realtime_tools::RealtimePublisher< std_msgs::Float64MultiArray > > extra_analog_inputs_publisher
Extra analog inputs real time publisher (+ accelerometer and gyroscope)
Definition: sr06.h:76
#define ETHERCAT_CAN_BRIDGE_DATA_SIZE
Definition: sr06.cpp:62
GYRZ
static Time now()
ANA1
std::string device_joint_prefix_
Definition: sr_edc.h:99
std::string device_id_
Definition: sr_edc.h:98
virtual void reinitialize_boards()
This function will call the reinitialization function for the boards attached to the CAN bus...
Definition: sr06.cpp:418
GYRX
EDC_COMMAND
#define ETHERCAT_STATUS_DATA_ADDRESS
Definition: sr06.cpp:65
boost::shared_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::EthercatDebug > > debug_publisher
Debug real time publisher: publishes the raw ethercat data.
Definition: sr06.h:107
#define SENSORS_NUM_0220
boost::shared_ptr< shadow_robot::SrMotorHandLib< ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND > > sr_hand_lib
Definition: sr06.h:98
virtual void get_board_id_and_can_bus(int board_id, int *can_bus, unsigned int *board_can_id)
Definition: sr06.cpp:424
bool flashing
Definition: sr_edc.h:95
Definition: sr06.h:55
virtual void packCommand(unsigned char *buffer, bool halt, bool reset)
packs the commands before sending them to the EtherCAT bus
Definition: sr06.cpp:226
virtual void construct(EtherCAT_SlaveHandler *sh, int &start_address)
Construct function, run at startup to set SyncManagers and FMMUs.
Definition: sr06.cpp:125
SR06()
Constructor of the SR06 driver.
Definition: sr06.cpp:78
#define ROS_DEBUG(...)


sr_edc_ethercat_drivers
Author(s): Ugo Cupcic, Yann Sionneau, Toni Oliver
autogenerated on Mon Feb 28 2022 23:50:53