00001
00028 #include <sr_edc_ethercat_drivers/sr08.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
00056
00057 BOOST_STATIC_ASSERT(sizeof(EDC_COMMAND) == 4);
00058 }
00059
00060 #define ETHERCAT_STATUS_DATA_SIZE sizeof(ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_STATUS)
00061 #define ETHERCAT_COMMAND_DATA_SIZE sizeof(ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_COMMAND)
00062
00063 #define ETHERCAT_CAN_BRIDGE_DATA_SIZE sizeof(ETHERCAT_CAN_BRIDGE_DATA)
00064
00065 #define ETHERCAT_COMMAND_DATA_ADDRESS PALM_0230_ETHERCAT_COMMAND_DATA_ADDRESS
00066 #define ETHERCAT_STATUS_DATA_ADDRESS PALM_0230_ETHERCAT_STATUS_DATA_ADDRESS
00067 #define ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS PALM_0230_ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS
00068 #define ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS PALM_0230_ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS
00069
00070
00071 PLUGINLIB_EXPORT_CLASS(SR08, EthercatDevice);
00072
00079 SR08::SR08()
00080 : zero_buffer_read(0),
00081 cycle_count(0)
00082 {
00083
00084
00085
00086
00087
00088
00089
00090
00091 }
00092
00126 void SR08::construct(EtherCAT_SlaveHandler *sh, int &start_address)
00127 {
00128 ROS_ASSERT(ETHERCAT_STATUS_0230_AGREED_SIZE == ETHERCAT_STATUS_DATA_SIZE);
00129 ROS_ASSERT(ETHERCAT_COMMAND_0230_AGREED_SIZE == ETHERCAT_COMMAND_DATA_SIZE);
00130
00131 SrEdc::construct(sh, start_address, ETHERCAT_COMMAND_DATA_SIZE, ETHERCAT_STATUS_DATA_SIZE,
00132 ETHERCAT_CAN_BRIDGE_DATA_SIZE,
00133 ETHERCAT_COMMAND_DATA_ADDRESS, ETHERCAT_STATUS_DATA_ADDRESS,
00134 ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS, ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS);
00135
00136 ROS_INFO("Finished constructing the SR08 driver");
00137 }
00138
00142 int SR08::initialize(hardware_interface::HardwareInterface *hw, bool allow_unprogrammed)
00143 {
00144 int retval = SR0X::initialize(hw, allow_unprogrammed);
00145
00146 if (retval != 0)
00147 {
00148 return retval;
00149 }
00150
00151 sr_hand_lib = boost::shared_ptr<shadow_robot::SrMotorHandLib<ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_STATUS,
00152 ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_COMMAND> >(
00153 new shadow_robot::SrMotorHandLib<ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_STATUS,
00154 ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_COMMAND>(hw, nodehandle_, nh_tilde_,
00155 device_id_, device_joint_prefix_));
00156
00157 ROS_INFO("ETHERCAT_STATUS_DATA_SIZE = %4d bytes", static_cast<int> (ETHERCAT_STATUS_DATA_SIZE));
00158 ROS_INFO("ETHERCAT_COMMAND_DATA_SIZE = %4d bytes", static_cast<int> (ETHERCAT_COMMAND_DATA_SIZE));
00159 ROS_INFO("ETHERCAT_CAN_BRIDGE_DATA_SIZE = %4d bytes", static_cast<int> (ETHERCAT_CAN_BRIDGE_DATA_SIZE));
00160
00161
00162 extra_analog_inputs_publisher.reset(
00163 new realtime_tools::RealtimePublisher<std_msgs::Float64MultiArray>(nodehandle_, "palm_extras", 10));
00164
00165
00166
00167 debug_publisher = boost::shared_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::EthercatDebug> >(
00168 new realtime_tools::RealtimePublisher<sr_robot_msgs::EthercatDebug>(nodehandle_, "debug_etherCAT_data", 4));
00169 return retval;
00170 }
00171
00178 void SR08::multiDiagnostics(vector<diagnostic_msgs::DiagnosticStatus> &vec, unsigned char *buffer)
00179 {
00180 diagnostic_updater::DiagnosticStatusWrapper &d(diagnostic_status_);
00181
00182 stringstream name;
00183 string prefix = device_id_.empty() ? device_id_ : (device_id_ + " ");
00184 d.name = prefix + "EtherCAT Dual CAN Palm";
00185 d.summary(d.OK, "OK");
00186 stringstream hwid;
00187 hwid << sh_->get_product_code() << "-" << sh_->get_serial();
00188 d.hardware_id = hwid.str();
00189
00190 d.clear();
00191 d.addf("Position", "%02d", sh_->get_ring_position());
00192 d.addf("Product Code", "%d", sh_->get_product_code());
00193 d.addf("Serial Number", "%d", sh_->get_serial());
00194 d.addf("Revision", "%d", sh_->get_revision());
00195 d.addf("Counter", "%d", ++counter_);
00196
00197 d.addf("PIC idle time (in microsecs)", "%d", sr_hand_lib->main_pic_idle_time);
00198 d.addf("Min PIC idle time (since last diagnostics)", "%d", sr_hand_lib->main_pic_idle_time_min);
00199
00200 sr_hand_lib->main_pic_idle_time_min = 1000;
00201
00202 this->ethercatDiagnostics(d, 2);
00203 vec.push_back(d);
00204
00205
00206 sr_hand_lib->add_diagnostics(vec, d);
00207
00208
00209 if (sr_hand_lib->tactiles != NULL)
00210 {
00211 sr_hand_lib->tactiles->add_diagnostics(vec, d);
00212 }
00213 }
00214
00230 void SR08::packCommand(unsigned char *buffer, bool halt, bool reset)
00231 {
00232 SrEdc::packCommand(buffer, halt, reset);
00233
00234 ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_COMMAND *command =
00235 reinterpret_cast<ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_COMMAND *>(buffer);
00236 ETHERCAT_CAN_BRIDGE_DATA *message = reinterpret_cast<ETHERCAT_CAN_BRIDGE_DATA *>(buffer + ETHERCAT_COMMAND_DATA_SIZE);
00237
00238 if (!flashing)
00239 {
00240 command->EDC_command = EDC_COMMAND_SENSOR_DATA;
00241 }
00242 else
00243 {
00244 command->EDC_command = EDC_COMMAND_CAN_DIRECT_MODE;
00245 }
00246
00247
00248
00249 sr_hand_lib->build_command(command);
00250
00251
00252
00253
00254 command->aux_data_type = TACTILE_SENSOR_TYPE_MCP320x_TACTILE;
00255
00256 ROS_DEBUG(
00257 "Sending command : Type : 0x%02X ; data : 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X"
00258 " 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X",
00259 command->to_motor_data_type,
00260 command->motor_data[0],
00261 command->motor_data[1],
00262 command->motor_data[2],
00263 command->motor_data[3],
00264 command->motor_data[4],
00265 command->motor_data[5],
00266 command->motor_data[6],
00267 command->motor_data[7],
00268 command->motor_data[8],
00269 command->motor_data[9],
00270 command->motor_data[10],
00271 command->motor_data[11],
00272 command->motor_data[12],
00273 command->motor_data[13],
00274 command->motor_data[14],
00275 command->motor_data[15],
00276 command->motor_data[16],
00277 command->motor_data[17],
00278 command->motor_data[18],
00279 command->motor_data[19]);
00280
00281 build_CAN_message(message);
00282 }
00283
00302 bool SR08::unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
00303 {
00304 ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_STATUS *status_data =
00305 reinterpret_cast<ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_STATUS *>(this_buffer + command_size_);
00306 ETHERCAT_CAN_BRIDGE_DATA *can_data =
00307 reinterpret_cast<ETHERCAT_CAN_BRIDGE_DATA *>(this_buffer + command_size_ + ETHERCAT_STATUS_DATA_SIZE);
00308
00309 static unsigned int num_rxed_packets = 0;
00310
00311 ++num_rxed_packets;
00312
00313
00314
00315 if (debug_publisher->trylock())
00316 {
00317 debug_publisher->msg_.header.stamp = ros::Time::now();
00318
00319 debug_publisher->msg_.sensors.clear();
00320 for (unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
00321 {
00322 debug_publisher->msg_.sensors.push_back(status_data->sensors[i]);
00323 }
00324
00325 debug_publisher->msg_.motor_data_type.data = static_cast<int> (status_data->motor_data_type);
00326 debug_publisher->msg_.which_motors = status_data->which_motors;
00327 debug_publisher->msg_.which_motor_data_arrived = status_data->which_motor_data_arrived;
00328 debug_publisher->msg_.which_motor_data_had_errors = status_data->which_motor_data_had_errors;
00329
00330 debug_publisher->msg_.motor_data_packet_torque.clear();
00331 debug_publisher->msg_.motor_data_packet_misc.clear();
00332 for (unsigned int i = 0; i < 10; ++i)
00333 {
00334 debug_publisher->msg_.motor_data_packet_torque.push_back(status_data->motor_data_packet[i].torque);
00335 debug_publisher->msg_.motor_data_packet_misc.push_back(status_data->motor_data_packet[i].misc);
00336 }
00337
00338 debug_publisher->msg_.tactile_data_type = static_cast<unsigned int> (
00339 static_cast<int32u>(status_data->tactile_data_type));
00340 debug_publisher->msg_.tactile_data_valid = static_cast<unsigned int> (
00341 static_cast<int16u> (status_data->tactile_data_valid));
00342 debug_publisher->msg_.tactile.clear();
00343 for (unsigned int i = 0; i < 5; ++i)
00344 {
00345 debug_publisher->msg_.tactile.push_back(
00346 static_cast<unsigned int> (static_cast<int16u> (status_data->tactile[i].word[0])));
00347 }
00348
00349 debug_publisher->msg_.idle_time_us = status_data->idle_time_us;
00350
00351 debug_publisher->unlockAndPublish();
00352 }
00353
00354 if (status_data->EDC_command == EDC_COMMAND_INVALID)
00355 {
00356
00357 ++zero_buffer_read;
00358 float percentage_packet_loss = 100.f * (static_cast<float>(zero_buffer_read) /
00359 static_cast<float>(num_rxed_packets));
00360
00361 ROS_DEBUG("Reception error detected : %d errors out of %d rxed packets (%2.3f%%) ; idle time %dus",
00362 zero_buffer_read, num_rxed_packets, percentage_packet_loss, status_data->idle_time_us);
00363 return true;
00364 }
00365
00366
00367
00368
00369 sr_hand_lib->update(status_data);
00370
00371
00372 if (cycle_count >= 10)
00373 {
00374
00375 if (sr_hand_lib->tactiles != NULL)
00376 {
00377 sr_hand_lib->tactiles->publish();
00378 }
00379
00380
00381 std_msgs::Float64MultiArray extra_analog_msg;
00382 extra_analog_msg.layout.dim.resize(3);
00383 extra_analog_msg.data.resize(3 + 3 + 4);
00384 std::vector<double> data;
00385
00386 extra_analog_msg.layout.dim[0].label = "accelerometer";
00387 extra_analog_msg.layout.dim[0].size = 3;
00388 extra_analog_msg.data[0] = status_data->sensors[ACCX];
00389 extra_analog_msg.data[1] = status_data->sensors[ACCY];
00390 extra_analog_msg.data[2] = status_data->sensors[ACCZ];
00391
00392 extra_analog_msg.layout.dim[1].label = "gyrometer";
00393 extra_analog_msg.layout.dim[1].size = 3;
00394 extra_analog_msg.data[3] = status_data->sensors[GYRX];
00395 extra_analog_msg.data[4] = status_data->sensors[GYRY];
00396 extra_analog_msg.data[5] = status_data->sensors[GYRZ];
00397
00398 extra_analog_msg.layout.dim[2].label = "analog_inputs";
00399 extra_analog_msg.layout.dim[2].size = 4;
00400 extra_analog_msg.data[6] = status_data->sensors[ANA0];
00401 extra_analog_msg.data[7] = status_data->sensors[ANA1];
00402 extra_analog_msg.data[8] = status_data->sensors[ANA2];
00403 extra_analog_msg.data[9] = status_data->sensors[ANA3];
00404
00405 if (extra_analog_inputs_publisher->trylock())
00406 {
00407 extra_analog_inputs_publisher->msg_ = extra_analog_msg;
00408 extra_analog_inputs_publisher->unlockAndPublish();
00409 }
00410
00411 cycle_count = 0;
00412 }
00413 ++cycle_count;
00414
00415
00416
00417 if (flashing & !can_packet_acked)
00418 {
00419 if (can_data_is_ack(can_data))
00420 {
00421 can_packet_acked = true;
00422 }
00423 }
00424
00425 return true;
00426 }
00427
00428 void SR08::reinitialize_boards()
00429 {
00430
00431 sr_hand_lib->reinitialize_motors();
00432 }
00433
00434 void SR08::get_board_id_and_can_bus(int board_id, int *can_bus, unsigned int *board_can_id)
00435 {
00436
00437
00438
00439 int motor_id_tmp = board_id;
00440 if (motor_id_tmp > 9)
00441 {
00442 motor_id_tmp -= 10;
00443 *can_bus = 2;
00444 }
00445 else
00446 {
00447 *can_bus = 1;
00448 }
00449
00450 *board_can_id = motor_id_tmp;
00451 }
00452
00453
00454
00455
00456
00457