00001
00027 #include <sr_edc_ethercat_drivers/sr_edc_muscle.h>
00028
00029 #include <realtime_tools/realtime_publisher.h>
00030
00031 #include <sstream>
00032 #include <string>
00033 #include <vector>
00034 #include <iomanip>
00035 #include <boost/foreach.hpp>
00036 #include <std_msgs/Int16.h>
00037 #include <math.h>
00038 #include <fcntl.h>
00039 #include <stdio.h>
00040 #include <pthread.h>
00041
00042 #include <sr_utilities/sr_math_utils.hpp>
00043
00044 using std::string;
00045 using std::stringstream;
00046 using std::vector;
00047
00048 #include <sr_external_dependencies/types_for_external.h>
00049
00050 #include <boost/static_assert.hpp>
00051
00052 namespace is_edc_command_32_bits
00053 {
00054
00055
00056 BOOST_STATIC_ASSERT(sizeof(EDC_COMMAND) == 4);
00057 }
00058
00059 #define ETHERCAT_STATUS_DATA_SIZE sizeof(ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS)
00060 #define ETHERCAT_COMMAND_DATA_SIZE sizeof(ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND)
00061
00062 #define ETHERCAT_CAN_BRIDGE_DATA_SIZE sizeof(ETHERCAT_CAN_BRIDGE_DATA)
00063
00064 #define ETHERCAT_COMMAND_DATA_ADDRESS PALM_0300_ETHERCAT_COMMAND_DATA_ADDRESS
00065 #define ETHERCAT_STATUS_DATA_ADDRESS PALM_0300_ETHERCAT_STATUS_DATA_ADDRESS
00066 #define ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS PALM_0300_ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS
00067 #define ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS PALM_0300_ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS
00068
00069
00070 PLUGINLIB_EXPORT_CLASS(SrEdcMuscle, EthercatDevice);
00071
00078 SrEdcMuscle::SrEdcMuscle()
00079 : zero_buffer_read(0),
00080 cycle_count(0)
00081 {
00082
00083
00084
00085
00086
00087
00088
00089
00090 }
00091
00125 void SrEdcMuscle::construct(EtherCAT_SlaveHandler *sh, int &start_address)
00126 {
00127 ROS_ASSERT(ETHERCAT_STATUS_0300_AGREED_SIZE == ETHERCAT_STATUS_DATA_SIZE);
00128 ROS_ASSERT(ETHERCAT_COMMAND_0300_AGREED_SIZE == ETHERCAT_COMMAND_DATA_SIZE);
00129
00130 SrEdc::construct(sh, start_address, ETHERCAT_COMMAND_DATA_SIZE, ETHERCAT_STATUS_DATA_SIZE,
00131 ETHERCAT_CAN_BRIDGE_DATA_SIZE,
00132 ETHERCAT_COMMAND_DATA_ADDRESS, ETHERCAT_STATUS_DATA_ADDRESS,
00133 ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS, ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS);
00134
00135 ROS_INFO("Finished constructing the SrEdcMuscle driver");
00136 }
00137
00141 int SrEdcMuscle::initialize(hardware_interface::HardwareInterface *hw, bool allow_unprogrammed)
00142 {
00143 int retval = SR0X::initialize(hw, allow_unprogrammed);
00144
00145 if (retval != 0)
00146 {
00147 return retval;
00148 }
00149
00150 sr_hand_lib = boost::shared_ptr<shadow_robot::SrMuscleHandLib<ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS,
00151 ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND> >(
00152 new shadow_robot::SrMuscleHandLib<ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS,
00153 ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND>(hw, nodehandle_, nh_tilde_,
00154 device_id_, device_joint_prefix_));
00155
00156 ROS_INFO("ETHERCAT_STATUS_DATA_SIZE = %4d bytes", static_cast<int> (ETHERCAT_STATUS_DATA_SIZE));
00157 ROS_INFO("ETHERCAT_COMMAND_DATA_SIZE = %4d bytes", static_cast<int> (ETHERCAT_COMMAND_DATA_SIZE));
00158 ROS_INFO("ETHERCAT_CAN_BRIDGE_DATA_SIZE = %4d bytes", static_cast<int> (ETHERCAT_CAN_BRIDGE_DATA_SIZE));
00159
00160
00161 extra_analog_inputs_publisher.reset(
00162 new realtime_tools::RealtimePublisher<std_msgs::Float64MultiArray>(nodehandle_, "palm_extras", 10));
00163
00164
00165
00166 debug_publisher = boost::shared_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::EthercatDebug> >(
00167 new realtime_tools::RealtimePublisher<sr_robot_msgs::EthercatDebug>(nodehandle_, "debug_etherCAT_data", 4));
00168 return retval;
00169 }
00170
00177 void SrEdcMuscle::multiDiagnostics(vector<diagnostic_msgs::DiagnosticStatus> &vec, unsigned char *buffer)
00178 {
00179 diagnostic_updater::DiagnosticStatusWrapper &d(diagnostic_status_);
00180
00181 stringstream name;
00182 string prefix = device_id_.empty() ? device_id_ : (device_id_ + " ");
00183 d.name = prefix + "EtherCAT Dual CAN Palm";
00184 d.summary(d.OK, "OK");
00185 stringstream hwid;
00186 hwid << sh_->get_product_code() << "-" << sh_->get_serial();
00187 d.hardware_id = hwid.str();
00188
00189 d.clear();
00190 d.addf("Position", "%02d", sh_->get_ring_position());
00191 d.addf("Product Code", "%d", sh_->get_product_code());
00192 d.addf("Serial Number", "%d", sh_->get_serial());
00193 d.addf("Revision", "%d", sh_->get_revision());
00194 d.addf("Counter", "%d", ++counter_);
00195
00196 d.addf("PIC idle time (in microsecs)", "%d", sr_hand_lib->main_pic_idle_time);
00197 d.addf("Min PIC idle time (since last diagnostics)", "%d", sr_hand_lib->main_pic_idle_time_min);
00198
00199 sr_hand_lib->main_pic_idle_time_min = 1000;
00200
00201 this->ethercatDiagnostics(d, 2);
00202 vec.push_back(d);
00203
00204
00205 sr_hand_lib->add_diagnostics(vec, d);
00206
00207
00208 if (sr_hand_lib->tactiles != NULL)
00209 {
00210 sr_hand_lib->tactiles->add_diagnostics(vec, d);
00211 }
00212 }
00213
00229 void SrEdcMuscle::packCommand(unsigned char *buffer, bool halt, bool reset)
00230 {
00231 SrEdc::packCommand(buffer, halt, reset);
00232
00233 ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND *command =
00234 reinterpret_cast<ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND *>(buffer);
00235 ETHERCAT_CAN_BRIDGE_DATA *message = reinterpret_cast<ETHERCAT_CAN_BRIDGE_DATA *>(buffer + ETHERCAT_COMMAND_DATA_SIZE);
00236
00237 if (!flashing)
00238 {
00239 command->EDC_command = EDC_COMMAND_SENSOR_DATA;
00240 }
00241 else
00242 {
00243 command->EDC_command = EDC_COMMAND_CAN_DIRECT_MODE;
00244 }
00245
00246
00247
00248 sr_hand_lib->build_command(command);
00249
00250 ROS_DEBUG(
00251 "Sending command : Type : 0x%02X ; data : 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X "
00252 "0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X",
00253 command->to_muscle_data_type,
00254 command->muscle_data[0],
00255 command->muscle_data[1],
00256 command->muscle_data[2],
00257 command->muscle_data[3],
00258 command->muscle_data[4],
00259 command->muscle_data[5],
00260 command->muscle_data[6],
00261 command->muscle_data[7],
00262 command->muscle_data[8],
00263 command->muscle_data[9],
00264 command->muscle_data[10],
00265 command->muscle_data[11],
00266 command->muscle_data[12],
00267 command->muscle_data[13],
00268 command->muscle_data[14],
00269 command->muscle_data[15],
00270 command->muscle_data[16],
00271 command->muscle_data[17],
00272 command->muscle_data[18],
00273 command->muscle_data[19]);
00274
00275 build_CAN_message(message);
00276 }
00277
00296 bool SrEdcMuscle::unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
00297 {
00298 ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS *status_data =
00299 reinterpret_cast<ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS *>(this_buffer + command_size_);
00300 ETHERCAT_CAN_BRIDGE_DATA *can_data =
00301 reinterpret_cast<ETHERCAT_CAN_BRIDGE_DATA *>(this_buffer + command_size_ + ETHERCAT_STATUS_DATA_SIZE);
00302
00303 static unsigned int num_rxed_packets = 0;
00304
00305 ++num_rxed_packets;
00306
00307
00308
00309 if (debug_publisher->trylock())
00310 {
00311 debug_publisher->msg_.header.stamp = ros::Time::now();
00312
00313 debug_publisher->msg_.sensors.clear();
00314 for (unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
00315 {
00316 debug_publisher->msg_.sensors.push_back(status_data->sensors[i]);
00317 }
00318
00319
00320
00321
00322
00323
00324 debug_publisher->msg_.motor_data_packet_torque.clear();
00325 debug_publisher->msg_.motor_data_packet_misc.clear();
00326
00327 for (unsigned int i = 0; i < 8; ++i)
00328 {
00329 debug_publisher->msg_.motor_data_packet_torque.push_back(
00330 (status_data->muscle_data_packet[i].packed.pressure0_H << 8) +
00331 (status_data->muscle_data_packet[i].packed.pressure0_M << 4) +
00332 status_data->muscle_data_packet[i].packed.pressure0_L);
00333 debug_publisher->msg_.motor_data_packet_torque.push_back(
00334 (status_data->muscle_data_packet[i].packed.pressure1_H << 8) +
00335 (status_data->muscle_data_packet[i].packed.pressure1_M << 4) +
00336 status_data->muscle_data_packet[i].packed.pressure1_L);
00337 debug_publisher->msg_.motor_data_packet_torque.push_back(
00338 (status_data->muscle_data_packet[i].packed.pressure2_H << 8) +
00339 (status_data->muscle_data_packet[i].packed.pressure2_M << 4) +
00340 status_data->muscle_data_packet[i].packed.pressure2_L);
00341 debug_publisher->msg_.motor_data_packet_torque.push_back(
00342 (status_data->muscle_data_packet[i].packed.pressure3_H << 8) +
00343 (status_data->muscle_data_packet[i].packed.pressure3_M << 4) +
00344 status_data->muscle_data_packet[i].packed.pressure3_L);
00345 debug_publisher->msg_.motor_data_packet_torque.push_back(
00346 (status_data->muscle_data_packet[i].packed.pressure4_H << 8) +
00347 (status_data->muscle_data_packet[i].packed.pressure4_M << 4) +
00348 status_data->muscle_data_packet[i].packed.pressure4_L);
00349 }
00350
00351
00352
00353
00354
00355
00356
00357 debug_publisher->msg_.tactile_data_type =
00358 static_cast<unsigned int> (static_cast<int32u> (status_data->tactile_data_type));
00359 debug_publisher->msg_.tactile_data_valid =
00360 static_cast<unsigned int> (static_cast<int16u> (status_data->tactile_data_valid));
00361 debug_publisher->msg_.tactile.clear();
00362 for (unsigned int i = 0; i < 5; ++i)
00363 {
00364 debug_publisher->msg_.tactile.push_back(
00365 static_cast<unsigned int> (static_cast<int16u> (status_data->tactile[i].word[0])));
00366 }
00367
00368 debug_publisher->msg_.idle_time_us = status_data->idle_time_us;
00369
00370 debug_publisher->unlockAndPublish();
00371 }
00372
00373 if (status_data->EDC_command == EDC_COMMAND_INVALID)
00374 {
00375
00376 ++zero_buffer_read;
00377 float percentage_packet_loss = 100.f * (static_cast<float>(zero_buffer_read)/ static_cast<float>(num_rxed_packets));
00378
00379 ROS_DEBUG("Reception error detected : %d errors out of %d rxed packets (%2.3f%%) ; idle time %dus",
00380 zero_buffer_read, num_rxed_packets, percentage_packet_loss, status_data->idle_time_us);
00381 return true;
00382 }
00383
00384
00385
00386
00387 sr_hand_lib->update(status_data);
00388
00389
00390 if (cycle_count >= 9)
00391 {
00392
00393 if (sr_hand_lib->tactiles != NULL)
00394 {
00395 sr_hand_lib->tactiles->publish();
00396 }
00397
00398
00399 std_msgs::Float64MultiArray extra_analog_msg;
00400 extra_analog_msg.layout.dim.resize(3);
00401 extra_analog_msg.data.resize(3 + 3 + 4);
00402 std::vector<double> data;
00403
00404 extra_analog_msg.layout.dim[0].label = "accelerometer";
00405 extra_analog_msg.layout.dim[0].size = 3;
00406 extra_analog_msg.data[0] = status_data->sensors[ACCX];
00407 extra_analog_msg.data[1] = status_data->sensors[ACCY];
00408 extra_analog_msg.data[2] = status_data->sensors[ACCZ];
00409
00410 extra_analog_msg.layout.dim[1].label = "gyrometer";
00411 extra_analog_msg.layout.dim[1].size = 3;
00412 extra_analog_msg.data[3] = status_data->sensors[GYRX];
00413 extra_analog_msg.data[4] = status_data->sensors[GYRY];
00414 extra_analog_msg.data[5] = status_data->sensors[GYRZ];
00415
00416 extra_analog_msg.layout.dim[2].label = "analog_inputs";
00417 extra_analog_msg.layout.dim[2].size = 4;
00418 extra_analog_msg.data[6] = status_data->sensors[ANA0];
00419 extra_analog_msg.data[7] = status_data->sensors[ANA1];
00420 extra_analog_msg.data[8] = status_data->sensors[ANA2];
00421 extra_analog_msg.data[9] = status_data->sensors[ANA3];
00422
00423 if (extra_analog_inputs_publisher->trylock())
00424 {
00425 extra_analog_inputs_publisher->msg_ = extra_analog_msg;
00426 extra_analog_inputs_publisher->unlockAndPublish();
00427 }
00428
00429 cycle_count = 0;
00430 }
00431 ++cycle_count;
00432
00433
00434
00435 if (flashing & !can_packet_acked)
00436 {
00437 if (can_data_is_ack(can_data))
00438 {
00439 can_packet_acked = true;
00440 }
00441 }
00442
00443 return true;
00444 }
00445
00446 void SrEdcMuscle::reinitialize_boards()
00447 {
00448
00449 sr_hand_lib->reinitialize_motors();
00450 }
00451
00452 void SrEdcMuscle::get_board_id_and_can_bus(int board_id, int *can_bus, unsigned int *board_can_id)
00453 {
00454
00455
00456
00457 int muscle_driver_board_id_tmp = board_id;
00458 if (muscle_driver_board_id_tmp > 1)
00459 {
00460 muscle_driver_board_id_tmp -= 2;
00461 *can_bus = 2;
00462 }
00463 else
00464 {
00465 *can_bus = 1;
00466 }
00467
00468 *board_can_id = muscle_driver_board_id_tmp;
00469 }
00470
00471
00472
00473
00474
00475