sr06.cpp
Go to the documentation of this file.
00001 
00028 #include <sr_edc_ethercat_drivers/sr06.h>
00029 
00030 #include <realtime_tools/realtime_publisher.h>
00031 
00032 #include <math.h>
00033 #include <sstream>
00034 #include <string>
00035 #include <vector>
00036 #include <iomanip>
00037 #include <boost/foreach.hpp>
00038 #include <std_msgs/Int16.h>
00039 #include <fcntl.h>
00040 #include <stdio.h>
00041 #include <pthread.h>
00042 
00043 #include <sr_utilities/sr_math_utils.hpp>
00044 
00045 using std::string;
00046 using std::stringstream;
00047 using std::vector;
00048 
00049 #include <sr_external_dependencies/types_for_external.h>
00050 
00051 #include <boost/static_assert.hpp>
00052 
00053 namespace is_edc_command_32_bits
00054 {
00055 // check is the EDC_COMMAND is 32bits on the computer
00056 // if not, fails
00057   BOOST_STATIC_ASSERT(sizeof(EDC_COMMAND) == 4);
00058 }  // namespace is_edc_command_32_bits
00059 
00060 #define ETHERCAT_STATUS_DATA_SIZE sizeof(ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS)
00061 #define ETHERCAT_COMMAND_DATA_SIZE sizeof(ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND)
00062 
00063 #define ETHERCAT_CAN_BRIDGE_DATA_SIZE sizeof(ETHERCAT_CAN_BRIDGE_DATA)
00064 
00065 #define ETHERCAT_COMMAND_DATA_ADDRESS                   PALM_0200_ETHERCAT_COMMAND_DATA_ADDRESS
00066 #define ETHERCAT_STATUS_DATA_ADDRESS                    PALM_0200_ETHERCAT_STATUS_DATA_ADDRESS
00067 #define ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS        PALM_0200_ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS
00068 #define ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS         PALM_0200_ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS
00069 
00070 
00071 PLUGINLIB_EXPORT_CLASS(SR06, EthercatDevice);
00072 
00079 SR06::SR06()
00080         : zero_buffer_read(0),
00081           cycle_count(0)
00082 {
00083   /*
00084     ROS_INFO("There are %d sensors", nb_sensors_const);
00085     ROS_INFO(     "device_pub_freq_const = %d", device_pub_freq_const      );
00086     ROS_INFO(        "ros_pub_freq_const = %d", ros_pub_freq_const         );
00087     ROS_INFO(            "max_iter_const = %d", max_iter_const             );
00088     ROS_INFO(          "nb_sensors_const = %d", nb_sensors_const           );
00089     ROS_INFO("nb_publish_by_unpack_const = %d", nb_publish_by_unpack_const );
00090    */
00091 }
00092 
00126 void SR06::construct(EtherCAT_SlaveHandler *sh, int &start_address)
00127 {
00128   SrEdc::construct(sh, start_address, ETHERCAT_COMMAND_DATA_SIZE, ETHERCAT_STATUS_DATA_SIZE,
00129                    ETHERCAT_CAN_BRIDGE_DATA_SIZE,
00130                    ETHERCAT_COMMAND_DATA_ADDRESS, ETHERCAT_STATUS_DATA_ADDRESS,
00131                    ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS, ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS);
00132 
00133   ROS_INFO("Finished constructing the SR06 driver");
00134 }
00135 
00139 int SR06::initialize(hardware_interface::HardwareInterface *hw, bool allow_unprogrammed)
00140 {
00141   int retval = SR0X::initialize(hw, allow_unprogrammed);
00142 
00143   if (retval != 0)
00144   {
00145     return retval;
00146   }
00147 
00148   sr_hand_lib = boost::shared_ptr<shadow_robot::SrMotorHandLib<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS,
00149           ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND> >(
00150           new shadow_robot::SrMotorHandLib<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS,
00151                   ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND>(hw, nodehandle_, nh_tilde_,
00152                                                                  device_id_, device_joint_prefix_));
00153 
00154   ROS_INFO("ETHERCAT_STATUS_DATA_SIZE      = %4d bytes", static_cast<int> (ETHERCAT_STATUS_DATA_SIZE));
00155   ROS_INFO("ETHERCAT_COMMAND_DATA_SIZE     = %4d bytes", static_cast<int> (ETHERCAT_COMMAND_DATA_SIZE));
00156   ROS_INFO("ETHERCAT_CAN_BRIDGE_DATA_SIZE  = %4d bytes", static_cast<int> (ETHERCAT_CAN_BRIDGE_DATA_SIZE));
00157 
00158   // initialise the publisher for the extra analog inputs, gyroscope and accelerometer on the palm
00159   extra_analog_inputs_publisher.reset(
00160           new realtime_tools::RealtimePublisher<std_msgs::Float64MultiArray>(nodehandle_, "palm_extras", 10));
00161 
00162 
00163   // Debug real time publisher: publishes the raw ethercat data
00164   debug_publisher = boost::shared_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::EthercatDebug> >(
00165           new realtime_tools::RealtimePublisher<sr_robot_msgs::EthercatDebug>(nodehandle_, "debug_etherCAT_data", 4));
00166   return retval;
00167 }
00168 
00175 void SR06::multiDiagnostics(vector<diagnostic_msgs::DiagnosticStatus> &vec, unsigned char *buffer)
00176 {
00177   diagnostic_updater::DiagnosticStatusWrapper &d(diagnostic_status_);
00178 
00179   stringstream name;
00180   string prefix = device_id_.empty() ? device_id_ : (device_id_ + " ");
00181   d.name = prefix + "EtherCAT Dual CAN Palm";
00182   d.summary(d.OK, "OK");
00183   stringstream hwid;
00184   hwid << sh_->get_product_code() << "-" << sh_->get_serial();
00185   d.hardware_id = hwid.str();
00186 
00187   d.clear();
00188   d.addf("Position", "%02d", sh_->get_ring_position());
00189   d.addf("Product Code", "%d", sh_->get_product_code());
00190   d.addf("Serial Number", "%d", sh_->get_serial());
00191   d.addf("Revision", "%d", sh_->get_revision());
00192   d.addf("Counter", "%d", ++counter_);
00193 
00194   d.addf("PIC idle time (in microsecs)", "%d", sr_hand_lib->main_pic_idle_time);
00195   d.addf("Min PIC idle time (since last diagnostics)", "%d", sr_hand_lib->main_pic_idle_time_min);
00196   // reset the idle time min to a big number, to get a fresh number on next diagnostic
00197   sr_hand_lib->main_pic_idle_time_min = 1000;
00198 
00199   this->ethercatDiagnostics(d, 2);
00200   vec.push_back(d);
00201 
00202   // Add the diagnostics from the hand
00203   sr_hand_lib->add_diagnostics(vec, d);
00204 
00205   // Add the diagnostics from the tactiles
00206   if (sr_hand_lib->tactiles != NULL)
00207   {
00208     sr_hand_lib->tactiles->add_diagnostics(vec, d);
00209   }
00210 }
00211 
00227 void SR06::packCommand(unsigned char *buffer, bool halt, bool reset)
00228 {
00229   SrEdc::packCommand(buffer, halt, reset);
00230 
00231   ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND *command =
00232           reinterpret_cast<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND *>(buffer);
00233   ETHERCAT_CAN_BRIDGE_DATA *message = reinterpret_cast<ETHERCAT_CAN_BRIDGE_DATA *>(buffer + ETHERCAT_COMMAND_DATA_SIZE);
00234 
00235   if (!flashing)
00236   {
00237     command->EDC_command = EDC_COMMAND_SENSOR_DATA;
00238   }
00239   else
00240   {
00241     command->EDC_command = EDC_COMMAND_CAN_DIRECT_MODE;
00242   }
00243 
00244   // alternate between even and uneven motors
00245   // and ask for the different informations.
00246   sr_hand_lib->build_command(command);
00247 
00248   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 "
00249                     "0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X",
00250             command->to_motor_data_type,
00251             command->motor_data[0],
00252             command->motor_data[1],
00253             command->motor_data[2],
00254             command->motor_data[3],
00255             command->motor_data[4],
00256             command->motor_data[5],
00257             command->motor_data[6],
00258             command->motor_data[7],
00259             command->motor_data[8],
00260             command->motor_data[9],
00261             command->motor_data[10],
00262             command->motor_data[11],
00263             command->motor_data[12],
00264             command->motor_data[13],
00265             command->motor_data[14],
00266             command->motor_data[15],
00267             command->motor_data[16],
00268             command->motor_data[17],
00269             command->motor_data[18],
00270             command->motor_data[19]);
00271 
00272   build_CAN_message(message);
00273 }
00274 
00293 bool SR06::unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
00294 {
00295   ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS *status_data =
00296           reinterpret_cast<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS *>(this_buffer + command_size_);
00297   ETHERCAT_CAN_BRIDGE_DATA *can_data = reinterpret_cast<ETHERCAT_CAN_BRIDGE_DATA *>(this_buffer + command_size_ +
00298                                                                                     ETHERCAT_STATUS_DATA_SIZE);
00299   //  int16u                                        *status_buffer = (int16u*)status_data;
00300   static unsigned int num_rxed_packets = 0;
00301 
00302   ++num_rxed_packets;
00303 
00304 
00305   // publishes the debug information (a slightly formatted version of the incoming ethercat packet):
00306   if (debug_publisher->trylock())
00307   {
00308     debug_publisher->msg_.header.stamp = ros::Time::now();
00309 
00310     debug_publisher->msg_.sensors.clear();
00311     for (unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
00312     {
00313       debug_publisher->msg_.sensors.push_back(status_data->sensors[i]);
00314     }
00315 
00316     debug_publisher->msg_.motor_data_type.data = static_cast<int> (status_data->motor_data_type);
00317     debug_publisher->msg_.which_motors = status_data->which_motors;
00318     debug_publisher->msg_.which_motor_data_arrived = status_data->which_motor_data_arrived;
00319     debug_publisher->msg_.which_motor_data_had_errors = status_data->which_motor_data_had_errors;
00320 
00321     debug_publisher->msg_.motor_data_packet_torque.clear();
00322     debug_publisher->msg_.motor_data_packet_misc.clear();
00323     for (unsigned int i = 0; i < 10; ++i)
00324     {
00325       debug_publisher->msg_.motor_data_packet_torque.push_back(status_data->motor_data_packet[i].torque);
00326       debug_publisher->msg_.motor_data_packet_misc.push_back(status_data->motor_data_packet[i].misc);
00327     }
00328 
00329     debug_publisher->msg_.tactile_data_type = static_cast<unsigned int>(
00330             static_cast<int32u>(status_data->tactile_data_type));
00331     debug_publisher->msg_.tactile_data_valid = static_cast<unsigned int> (
00332             static_cast<int16u> (status_data->tactile_data_valid));
00333     debug_publisher->msg_.tactile.clear();
00334     for (unsigned int i = 0; i < 5; ++i)
00335     {
00336       debug_publisher->msg_.tactile.push_back(
00337               static_cast<unsigned int> (static_cast<int16u> (status_data->tactile[i].word[0])));
00338     }
00339 
00340     debug_publisher->msg_.idle_time_us = status_data->idle_time_us;
00341 
00342     debug_publisher->unlockAndPublish();
00343   }
00344 
00345   if (status_data->EDC_command == EDC_COMMAND_INVALID)
00346   {
00347     // received empty message: the pic is not writing to its mailbox.
00348     ++zero_buffer_read;
00349     float percentage_packet_loss = 100.f * (static_cast<float>(zero_buffer_read) /
00350                                             static_cast<float>(num_rxed_packets));
00351 
00352     ROS_DEBUG("Reception error detected : %d errors out of %d rxed packets (%2.3f%%) ; idle time %dus",
00353               zero_buffer_read, num_rxed_packets, percentage_packet_loss, status_data->idle_time_us);
00354     return true;
00355   }
00356 
00357   // We received a coherent message.
00358   // Update the library (positions, diagnostics values, actuators, etc...)
00359   // with the received information
00360   sr_hand_lib->update(status_data);
00361 
00362   // Now publish the additional data at 100Hz (every 10 cycles)
00363   if (cycle_count >= 10)
00364   {
00365     // publish tactiles if we have them
00366     if (sr_hand_lib->tactiles != NULL)
00367     {
00368       sr_hand_lib->tactiles->publish();
00369     }
00370 
00371     // And we also publish the additional data (accelerometer / gyroscope / analog inputs)
00372     std_msgs::Float64MultiArray extra_analog_msg;
00373     extra_analog_msg.layout.dim.resize(3);
00374     extra_analog_msg.data.resize(3 + 3 + 4);
00375     std::vector<double> data;
00376 
00377     extra_analog_msg.layout.dim[0].label = "accelerometer";
00378     extra_analog_msg.layout.dim[0].size = 3;
00379     extra_analog_msg.data[0] = status_data->sensors[ACCX];
00380     extra_analog_msg.data[1] = status_data->sensors[ACCY];
00381     extra_analog_msg.data[2] = status_data->sensors[ACCZ];
00382 
00383     extra_analog_msg.layout.dim[1].label = "gyrometer";
00384     extra_analog_msg.layout.dim[1].size = 3;
00385     extra_analog_msg.data[3] = status_data->sensors[GYRX];
00386     extra_analog_msg.data[4] = status_data->sensors[GYRY];
00387     extra_analog_msg.data[5] = status_data->sensors[GYRZ];
00388 
00389     extra_analog_msg.layout.dim[2].label = "analog_inputs";
00390     extra_analog_msg.layout.dim[2].size = 4;
00391     extra_analog_msg.data[6] = status_data->sensors[ANA0];
00392     extra_analog_msg.data[7] = status_data->sensors[ANA1];
00393     extra_analog_msg.data[8] = status_data->sensors[ANA2];
00394     extra_analog_msg.data[9] = status_data->sensors[ANA3];
00395 
00396     if (extra_analog_inputs_publisher->trylock())
00397     {
00398       extra_analog_inputs_publisher->msg_ = extra_analog_msg;
00399       extra_analog_inputs_publisher->unlockAndPublish();
00400     }
00401 
00402     cycle_count = 0;
00403   }
00404   ++cycle_count;
00405 
00406 
00407   // If we're flashing, check is the packet has been acked
00408   if (flashing & !can_packet_acked)
00409   {
00410     if (can_data_is_ack(can_data))
00411     {
00412       can_packet_acked = true;
00413     }
00414   }
00415 
00416   return true;
00417 }
00418 
00419 void SR06::reinitialize_boards()
00420 {
00421   // Reinitialize motors information
00422   sr_hand_lib->reinitialize_motors();
00423 }
00424 
00425 void SR06::get_board_id_and_can_bus(int board_id, int *can_bus, unsigned int *board_can_id)
00426 {
00427   // We're using 2 can busses,
00428   // if motor id is between 0 and 9, then we're using the can_bus 1
00429   // else, we're using the can bus 2.
00430   int motor_id_tmp = board_id;
00431   if (motor_id_tmp > 9)
00432   {
00433     motor_id_tmp -= 10;
00434     *can_bus = 2;
00435   }
00436   else
00437   {
00438     *can_bus = 1;
00439   }
00440 
00441   *board_can_id = motor_id_tmp;
00442 }
00443 
00444 /* For the emacs weenies in the crowd.
00445    Local Variables:
00446    c-basic-offset: 2
00447    End:
00448  */


sr_edc_ethercat_drivers
Author(s): Ugo Cupcic, Yann Sionneau, Toni Oliver
autogenerated on Mon Jul 1 2019 20:06:31