00001
00028 #include "sr_robot_lib/sr_muscle_robot_lib.hpp"
00029 #include <string>
00030 #include <utility>
00031 #include <map>
00032 #include <vector>
00033 #include <boost/foreach.hpp>
00034
00035 #include <sys/time.h>
00036
00037 #include <ros/ros.h>
00038
00039 #include <controller_manager_msgs/ListControllers.h>
00040
00041 #define SERIOUS_ERROR_FLAGS PALM_0300_EDC_SERIOUS_ERROR_FLAGS
00042 #define error_flag_names palm_0300_edc_error_flag_names
00043
00044
00045 using std::vector;
00046 using std::string;
00047 using std::pair;
00048 using std::map;
00049 using std::ostringstream;
00050 using sr_actuator::SrMuscleActuator;
00051 using shadow_joints::CalibrationMap;
00052 using shadow_joints::Joint;
00053 using shadow_joints::JointToSensor;
00054 using shadow_joints::JointToMuscle;
00055 using shadow_joints::MuscleWrapper;
00056 using shadow_joints::MuscleDriver;
00057 using shadow_joints::PartialJointToSensor;
00058 using generic_updater::MuscleUpdater;
00059 using boost::shared_ptr;
00060 using boost::static_pointer_cast;
00061 using boost::shared_ptr;
00062
00063 namespace shadow_robot
00064 {
00065 template<class StatusType, class CommandType>
00066 const double SrMuscleRobotLib<StatusType, CommandType>::timeout = 5.0;
00067
00068 template<class StatusType, class CommandType>
00069 SrMuscleRobotLib<StatusType, CommandType>::SrMuscleRobotLib(hardware_interface::HardwareInterface *hw,
00070 ros::NodeHandle nh, ros::NodeHandle nhtilde,
00071 string device_id, string joint_prefix)
00072 : SrRobotLib<StatusType, CommandType>(hw, nh, nhtilde, device_id, joint_prefix),
00073 muscle_current_state(operation_mode::device_update_state::INITIALIZATION), init_max_duration(timeout),
00074 lock_init_timeout_(shared_ptr<boost::mutex>(new boost::mutex())),
00075
00076
00077 check_init_timeout_timer(this->nh_tilde.createTimer(init_max_duration,
00078 boost::bind(
00079 &SrMuscleRobotLib<StatusType,
00080 CommandType>::init_timer_callback,
00081 this, _1), true)),
00082 pressure_calibration_map_(read_pressure_calibration())
00083 {
00084 #ifdef DEBUG_PUBLISHER
00085 this->debug_muscle_indexes_and_data.resize(this->nb_debug_publishers_const);
00086 for (int i = 0; i < this->nb_debug_publishers_const; ++i)
00087 {
00088 ostringstream ss;
00089 ss << "srh/debug_" << i;
00090 this->debug_publishers.push_back(this->node_handle.template advertise<std_msgs::Int16>(ss.str().c_str(), 100));
00091 }
00092 #endif
00093 }
00094
00095 template<class StatusType, class CommandType>
00096 CalibrationMap SrMuscleRobotLib<StatusType, CommandType>::read_pressure_calibration()
00097 {
00098 ROS_INFO("Reading pressure calibration");
00099 CalibrationMap pressure_calibration;
00100 string param_name = "sr_pressure_calibrations";
00101
00102 XmlRpc::XmlRpcValue calib;
00103 this->nodehandle_.getParam(param_name, calib);
00104 ROS_ASSERT(calib.getType() == XmlRpc::XmlRpcValue::TypeArray);
00105
00106 for (int32_t index_cal = 0; index_cal < calib.size(); ++index_cal)
00107 {
00108
00109
00110 ROS_ASSERT(calib[index_cal][0].getType() == XmlRpc::XmlRpcValue::TypeString);
00111 ROS_ASSERT(calib[index_cal][1].getType() == XmlRpc::XmlRpcValue::TypeArray);
00112
00113 string joint_name = static_cast<string> (calib[index_cal][0]);
00114 vector<joint_calibration::Point> calib_table_tmp;
00115
00116
00117 for (int32_t index_table = 0; index_table < calib[index_cal][1].size(); ++index_table)
00118 {
00119 ROS_ASSERT(calib[index_cal][1][index_table].getType() == XmlRpc::XmlRpcValue::TypeArray);
00120
00121 ROS_ASSERT(calib[index_cal][1][index_table].size() == 2);
00122 ROS_ASSERT(calib[index_cal][1][index_table][0].getType() == XmlRpc::XmlRpcValue::TypeDouble);
00123 ROS_ASSERT(calib[index_cal][1][index_table][1].getType() == XmlRpc::XmlRpcValue::TypeDouble);
00124
00125
00126 joint_calibration::Point point_tmp;
00127 point_tmp.raw_value = static_cast<double> (calib[index_cal][1][index_table][0]);
00128 point_tmp.calibrated_value = static_cast<double> (calib[index_cal][1][index_table][1]);
00129 calib_table_tmp.push_back(point_tmp);
00130 }
00131
00132 pressure_calibration.insert(joint_name, shared_ptr<shadow_robot::JointCalibration>(
00133 new shadow_robot::JointCalibration(calib_table_tmp)));
00134 }
00135
00136 return pressure_calibration;
00137 }
00138
00139 template<class StatusType, class CommandType>
00140 void SrMuscleRobotLib<StatusType, CommandType>::update(StatusType *status_data)
00141 {
00142
00143 this->main_pic_idle_time = status_data->idle_time_us;
00144 if (status_data->idle_time_us < this->main_pic_idle_time_min)
00145 {
00146 this->main_pic_idle_time_min = status_data->idle_time_us;
00147 }
00148
00149
00150 struct timeval tv;
00151 double timestamp = 0.0;
00152 if (gettimeofday(&tv, NULL))
00153 {
00154 ROS_WARN("SrMuscleRobotLib: Failed to get system time, timestamp in state will be zero");
00155 }
00156 else
00157 {
00158 timestamp = static_cast<double>(tv.tv_sec) + static_cast<double>(tv.tv_usec) / 1.0e+6;
00159 }
00160
00161
00162 this->update_tactile_info(status_data);
00163
00164
00165 for (vector<MuscleDriver>::iterator muscle_driver_tmp = this->muscle_drivers_vector_.begin();
00166 muscle_driver_tmp != this->muscle_drivers_vector_.end();
00167 ++muscle_driver_tmp)
00168 {
00169 read_muscle_driver_data(muscle_driver_tmp, status_data);
00170 }
00171
00172
00173 for (vector<Joint>::iterator joint_tmp = this->joints_vector.begin();
00174 joint_tmp != this->joints_vector.end();
00175 ++joint_tmp)
00176 {
00177 if (!joint_tmp->has_actuator)
00178 {
00179 continue;
00180 }
00181
00182 SrMuscleActuator *actuator = this->get_joint_actuator(joint_tmp);
00183 shared_ptr<MuscleWrapper> muscle_wrapper = static_pointer_cast<MuscleWrapper>(joint_tmp->actuator_wrapper);
00184
00185
00186 if (this->tactiles != NULL)
00187 {
00188 actuator->muscle_state_.tactiles_ = this->tactiles->get_tactile_data();
00189 }
00190
00191 this->process_position_sensor_data(joint_tmp, status_data, timestamp);
00192
00193
00194 if ((muscle_wrapper->muscle_driver_id[0] == -1))
00195 {
00196 continue;
00197 }
00198
00199 read_additional_muscle_data(joint_tmp, status_data);
00200 }
00201 }
00202
00203 template<class StatusType, class CommandType>
00204 void SrMuscleRobotLib<StatusType, CommandType>::build_command(CommandType *command)
00205 {
00206 if (muscle_current_state == operation_mode::device_update_state::INITIALIZATION)
00207 {
00208 muscle_current_state = muscle_updater_->build_init_command(command);
00209 }
00210 else
00211 {
00212
00213 muscle_current_state = muscle_updater_->build_command(command);
00214 }
00215
00216
00217 this->build_tactile_command(command);
00218
00220
00221
00222
00223 if (reset_muscle_driver_queue.empty())
00224 {
00225 command->to_muscle_data_type = MUSCLE_DEMAND_VALVES;
00226
00227
00228 for (vector<Joint>::iterator joint_tmp = this->joints_vector.begin();
00229 joint_tmp != this->joints_vector.end();
00230 ++joint_tmp)
00231 {
00232 if (joint_tmp->has_actuator)
00233 {
00234 shared_ptr<MuscleWrapper> muscle_wrapper = static_pointer_cast<MuscleWrapper>(joint_tmp->actuator_wrapper);
00235 SrMuscleActuator *muscle_actuator = static_cast<SrMuscleActuator *> (muscle_wrapper->actuator);
00236
00237 unsigned int muscle_driver_id_0 = muscle_wrapper->muscle_driver_id[0];
00238 unsigned int muscle_driver_id_1 = muscle_wrapper->muscle_driver_id[1];
00239 unsigned int muscle_id_0 = muscle_wrapper->muscle_id[0];
00240 unsigned int muscle_id_1 = muscle_wrapper->muscle_id[1];
00241
00242 if (!this->nullify_demand_)
00243 {
00244 set_valve_demand(&(command->muscle_data[(muscle_driver_id_0 * 10 + muscle_id_0) / 2]),
00245 muscle_actuator->muscle_command_.valve_[0], ((uint8_t) muscle_id_0) & 0x01);
00246 set_valve_demand(&(command->muscle_data[(muscle_driver_id_1 * 10 + muscle_id_1) / 2]),
00247 muscle_actuator->muscle_command_.valve_[1], ((uint8_t) muscle_id_1) & 0x01);
00248
00249 muscle_actuator->muscle_state_.last_commanded_valve_[0] = muscle_actuator->muscle_command_.valve_[0];
00250 muscle_actuator->muscle_state_.last_commanded_valve_[1] = muscle_actuator->muscle_command_.valve_[1];
00251 }
00252 else
00253 {
00254
00255 set_valve_demand(&(command->muscle_data[(muscle_driver_id_0 * 10 + muscle_id_0) / 2]), 0,
00256 ((uint8_t) muscle_id_0) & 0x01);
00257 set_valve_demand(&(command->muscle_data[(muscle_driver_id_1 * 10 + muscle_id_1) / 2]), 0,
00258 ((uint8_t) muscle_id_1) & 0x01);
00259
00260 muscle_actuator->muscle_state_.last_commanded_valve_[0] = 0;
00261 muscle_actuator->muscle_state_.last_commanded_valve_[1] = 0;
00262 }
00263
00264 #ifdef DEBUG_PUBLISHER
00265
00266
00267
00268 int publisher_index = 0;
00269 shared_ptr<pair<int, int> > debug_pair;
00270 if (this->debug_mutex.try_lock())
00271 {
00272 BOOST_FOREACH(debug_pair, this->debug_muscle_indexes_and_data)
00273 {
00274 if (debug_pair != NULL)
00275 {
00276 MuscleWrapper* actuator_wrapper = static_cast<MuscleWrapper*> (joint_tmp->actuator_wrapper.get());
00277
00278 if (debug_pair->first == actuator_wrapper->muscle_id[0])
00279 {
00280
00281 if (debug_pair->second == -1)
00282 {
00283 this->msg_debug.data = joint_tmp->actuator_wrapper->actuator->command_.effort_;
00284 this->debug_publishers[publisher_index].publish(this->msg_debug);
00285 }
00286 }
00287 }
00288 publisher_index++;
00289 }
00290
00291 this->debug_mutex.unlock();
00292 }
00293 #endif
00294 }
00295 }
00296 }
00297 else
00298 {
00299
00300
00301 command->to_muscle_data_type = MUSCLE_SYSTEM_RESET;
00302
00303 while (!reset_muscle_driver_queue.empty())
00304 {
00305 int16_t muscle_driver_id = reset_muscle_driver_queue.front();
00306 reset_muscle_driver_queue.pop();
00307
00308
00309 for (vector<MuscleDriver>::iterator driver = this->muscle_drivers_vector_.begin();
00310 driver != this->muscle_drivers_vector_.end();
00311 ++driver)
00312 {
00313 if (driver->muscle_driver_id == muscle_driver_id)
00314 {
00315 driver->can_msgs_transmitted_ = 0;
00316 driver->can_msgs_received_ = 0;
00317 }
00318 }
00319
00320
00321
00322 crc_unions::union16 to_send;
00323 to_send.byte[1] = MUSCLE_SYSTEM_RESET_KEY >> 8;
00324 if (muscle_driver_id > 1)
00325 {
00326 to_send.byte[0] = muscle_driver_id - 2;
00327 }
00328 else
00329 {
00330 to_send.byte[0] = muscle_driver_id;
00331 }
00332
00333 command->muscle_data[muscle_driver_id * 5] = to_send.byte[0];
00334 command->muscle_data[muscle_driver_id * 5 + 1] = to_send.byte[1];
00335 }
00336 }
00337 }
00338
00339 template<class StatusType, class CommandType>
00340 inline void SrMuscleRobotLib<StatusType, CommandType>::set_valve_demand(uint8_t *muscle_data_byte_to_set,
00341 int8_t valve_value, uint8_t shift)
00342 {
00343 uint8_t tmp_valve = 0;
00344
00345
00346
00347
00348 if (valve_value < 0)
00349 {
00350
00351 tmp_valve = -valve_value;
00352
00353 tmp_valve = (~tmp_valve) & 0x0F;
00354
00355 tmp_valve = tmp_valve + 1;
00356 }
00357 else
00358 {
00359 tmp_valve = valve_value & 0x0F;
00360 }
00361
00362
00363
00364
00365
00366 *muscle_data_byte_to_set &= (0xF0 >> (shift * 4));
00367
00368 *muscle_data_byte_to_set |= (tmp_valve << (shift * 4));
00369 }
00370
00371 template<class StatusType, class CommandType>
00372 void SrMuscleRobotLib<StatusType, CommandType>::add_diagnostics(vector<diagnostic_msgs::DiagnosticStatus> &vec,
00373 diagnostic_updater::DiagnosticStatusWrapper &d)
00374 {
00375 for (vector<Joint>::iterator joint = this->joints_vector.begin();
00376 joint != this->joints_vector.end();
00377 ++joint)
00378 {
00379 ostringstream name("");
00380 string prefix = this->device_id_.empty() ? this->device_id_ : (this->device_id_ + " ");
00381 name << prefix << "SRDMuscle " << joint->joint_name;
00382 d.name = name.str();
00383
00384 if (joint->has_actuator)
00385 {
00386 shared_ptr<MuscleWrapper> actuator_wrapper = static_pointer_cast<MuscleWrapper>(joint->actuator_wrapper);
00387 SrMuscleActuator *actuator = get_joint_actuator(joint);
00388
00389 if (actuator_wrapper->actuator_ok)
00390 {
00391 if (actuator_wrapper->bad_data)
00392 {
00393 d.summary(d.WARN, "WARNING, bad CAN data received");
00394
00395 d.clear();
00396 d.addf("Muscle ID 0", "%d", actuator_wrapper->muscle_id[0]);
00397 d.addf("Muscle driver ID 0", "%d", actuator_wrapper->muscle_driver_id[0]);
00398 d.addf("Muscle ID 1", "%d", actuator_wrapper->muscle_id[1]);
00399 d.addf("Muscle driver ID 1", "%d", actuator_wrapper->muscle_driver_id[1]);
00400 }
00401 else
00402 {
00403 d.summary(d.OK, "OK");
00404
00405 d.clear();
00406 d.addf("Muscle ID 0", "%d", actuator_wrapper->muscle_id[0]);
00407 d.addf("Muscle driver ID 0", "%d", actuator_wrapper->muscle_driver_id[0]);
00408 d.addf("Muscle ID 1", "%d", actuator_wrapper->muscle_id[1]);
00409 d.addf("Muscle driver ID 1", "%d", actuator_wrapper->muscle_driver_id[1]);
00410
00411 d.addf("Unfiltered position", "%f", actuator->muscle_state_.position_unfiltered_);
00412
00413 d.addf("Last Commanded Valve 0", "%d", actuator->muscle_state_.last_commanded_valve_[0]);
00414 d.addf("Last Commanded Valve 1", "%d", actuator->muscle_state_.last_commanded_valve_[1]);
00415
00416 d.addf("Unfiltered Pressure 0", "%u", actuator->muscle_state_.pressure_[0]);
00417 d.addf("Unfiltered Pressure 1", "%u", actuator->muscle_state_.pressure_[1]);
00418
00419 d.addf("Position", "%f", actuator->state_.position_);
00420 }
00421 }
00422 else
00423 {
00424 d.summary(d.ERROR, "Muscle error");
00425 d.clear();
00426 d.addf("Muscle ID 0", "%d", actuator_wrapper->muscle_id[0]);
00427 d.addf("Muscle driver ID 0", "%d", actuator_wrapper->muscle_driver_id[0]);
00428 d.addf("Muscle ID 1", "%d", actuator_wrapper->muscle_id[1]);
00429 d.addf("Muscle driver ID 1", "%d", actuator_wrapper->muscle_driver_id[1]);
00430 }
00431 }
00432 else
00433 {
00434 d.summary(d.OK, "No muscle associated to this joint");
00435 d.clear();
00436 }
00437 vec.push_back(d);
00438 }
00439
00440 for (vector<MuscleDriver>::iterator muscle_driver = this->muscle_drivers_vector_.begin();
00441 muscle_driver != this->muscle_drivers_vector_.end();
00442 ++muscle_driver)
00443 {
00444 ostringstream name("");
00445 name << "Muscle driver " << muscle_driver->muscle_driver_id;
00446 d.name = name.str();
00447
00448 if (muscle_driver->driver_ok)
00449 {
00450 if (muscle_driver->bad_data)
00451 {
00452 d.summary(d.WARN, "WARNING, bad CAN data received");
00453
00454 d.clear();
00455 d.addf("Muscle Driver ID", "%d", muscle_driver->muscle_driver_id);
00456 }
00457 else
00458 {
00459 d.summary(d.OK, "OK");
00460
00461 d.clear();
00462 d.addf("Muscle Driver ID", "%d", muscle_driver->muscle_driver_id);
00463 d.addf("Serial Number", "%d", muscle_driver->serial_number);
00464 d.addf("Assembly date", "%d / %d / %d", muscle_driver->assembly_date_day, muscle_driver->assembly_date_month,
00465 muscle_driver->assembly_date_year);
00466
00467 d.addf("Number of CAN messages received", "%lld", muscle_driver->can_msgs_received_);
00468 d.addf("Number of CAN messages transmitted", "%lld", muscle_driver->can_msgs_transmitted_);
00469
00470 if (muscle_driver->firmware_modified_)
00471 {
00472 d.addf("Firmware git revision (server / pic / modified)", "%d / %d / True",
00473 muscle_driver->server_firmware_git_revision_, muscle_driver->pic_firmware_git_revision_);
00474 }
00475 else
00476 {
00477 d.addf("Firmware git revision (server / pic / modified)", "%d / %d / False",
00478 muscle_driver->server_firmware_git_revision_, muscle_driver->pic_firmware_git_revision_);
00479 }
00480 }
00481 }
00482 else
00483 {
00484 d.summary(d.ERROR, "Muscle Driver error");
00485 d.clear();
00486 d.addf("Muscle Driver ID", "%d", muscle_driver->muscle_driver_id);
00487 }
00488
00489 vec.push_back(d);
00490 }
00491 }
00492
00493 template<class StatusType, class CommandType>
00494 void SrMuscleRobotLib<StatusType, CommandType>::read_additional_muscle_data(vector<Joint>::iterator joint_tmp,
00495 StatusType *status_data)
00496 {
00497 if (!joint_tmp->has_actuator)
00498 {
00499 return;
00500 }
00501
00502 int packet_offset_muscle_0 = 0;
00503 int packet_offset_muscle_1 = 0;
00504
00505 shared_ptr<MuscleWrapper> muscle_wrapper = static_pointer_cast<MuscleWrapper>(joint_tmp->actuator_wrapper);
00506
00507
00508 if (muscle_wrapper->muscle_id[0] >= NUM_PRESSURE_SENSORS_PER_MESSAGE)
00509 {
00510 packet_offset_muscle_0 = 1;
00511 }
00512
00513 if (muscle_wrapper->muscle_id[1] >= NUM_PRESSURE_SENSORS_PER_MESSAGE)
00514 {
00515 packet_offset_muscle_1 = 1;
00516 }
00517
00518
00519
00520
00521
00522 muscle_wrapper->actuator_ok = sr_math_utils::is_bit_mask_index_true(status_data->which_muscle_data_arrived,
00523 muscle_wrapper->muscle_driver_id[0] * 2 +
00524 packet_offset_muscle_0)
00525 && sr_math_utils::is_bit_mask_index_true(status_data->which_muscle_data_arrived,
00526 muscle_wrapper->muscle_driver_id[1] * 2 +
00527 packet_offset_muscle_1);
00528
00529
00530
00531
00532
00533
00534
00535
00536
00537
00538
00539
00540
00541 if (muscle_wrapper->actuator_ok)
00542 {
00543 SrMuscleActuator *actuator = static_cast<SrMuscleActuator *> (joint_tmp->actuator_wrapper->actuator);
00544 MuscleWrapper *actuator_wrapper = static_cast<MuscleWrapper *> (joint_tmp->actuator_wrapper.get());
00545
00546 #ifdef DEBUG_PUBLISHER
00547 int publisher_index = 0;
00548
00549
00550
00551 shared_ptr<pair<int, int> > debug_pair;
00552
00553 if (this->debug_mutex.try_lock())
00554 {
00555 BOOST_FOREACH(debug_pair, this->debug_muscle_indexes_and_data)
00556 {
00557 if (debug_pair != NULL)
00558 {
00559
00560 if (debug_pair->first == actuator_wrapper->muscle_id[0])
00561 {
00562
00563 if (debug_pair->second > 0)
00564 {
00565
00566 if (debug_pair->second == status_data->muscle_data_type)
00567 {
00568
00569
00570 this->msg_debug.data = 0;
00571 this->debug_publishers[publisher_index].publish(this->msg_debug);
00572 }
00573 }
00574 }
00575 }
00576 publisher_index++;
00577 }
00578
00579 this->debug_mutex.unlock();
00580 }
00581 #endif
00582
00583
00584 unsigned int p1 = 0;
00585 switch (status_data->muscle_data_type)
00586 {
00587 case MUSCLE_DATA_PRESSURE:
00588
00589 for (int i = 0; i < 2; ++i)
00590 {
00591 p1 = get_muscle_pressure(muscle_wrapper->muscle_driver_id[i], muscle_wrapper->muscle_id[i], status_data);
00592 string name = joint_tmp->joint_name + "_" + boost::lexical_cast<string>(i);
00593
00594
00595 pressure_calibration_tmp_ = pressure_calibration_map_.find(name);
00596 double bar = pressure_calibration_tmp_->compute(static_cast<double> (p1));
00597 if (bar < 0.0)
00598 {
00599 bar = 0.0;
00600 }
00601 actuator->muscle_state_.pressure_[i] = static_cast<int16u> (bar);
00602 }
00603
00604
00605
00606
00607
00608
00609
00610
00611
00612
00613
00614
00615
00616
00617 #ifdef DEBUG_PUBLISHER
00618 if (actuator_wrapper->muscle_id[0] == 8)
00619 {
00620
00621
00622
00623 }
00624 #endif
00625 break;
00626
00627
00628 default:
00629 break;
00630 }
00631 }
00632 }
00633
00634 template<class StatusType, class CommandType>
00635 unsigned int SrMuscleRobotLib<StatusType, CommandType>::get_muscle_pressure(int muscle_driver_id, int muscle_id,
00636 StatusType *status_data)
00637 {
00638 unsigned int muscle_pressure = 0;
00639 int packet_offset = 0;
00640 int muscle_index = muscle_id;
00641
00642
00643 if (muscle_id >= NUM_PRESSURE_SENSORS_PER_MESSAGE)
00644 {
00645 packet_offset = 1;
00646 muscle_index = muscle_id - NUM_PRESSURE_SENSORS_PER_MESSAGE;
00647 }
00648
00649 switch (muscle_index)
00650 {
00651 case 0:
00652 muscle_pressure =
00653 (status_data->muscle_data_packet[muscle_driver_id * 2 + packet_offset].packed.pressure0_H << 8)
00654 + (status_data->muscle_data_packet[muscle_driver_id * 2 + packet_offset].packed.pressure0_M << 4)
00655 + status_data->muscle_data_packet[muscle_driver_id * 2 + packet_offset].packed.pressure0_L;
00656 break;
00657
00658 case 1:
00659 muscle_pressure =
00660 (status_data->muscle_data_packet[muscle_driver_id * 2 + packet_offset].packed.pressure1_H << 8)
00661 + (status_data->muscle_data_packet[muscle_driver_id * 2 + packet_offset].packed.pressure1_M << 4)
00662 + status_data->muscle_data_packet[muscle_driver_id * 2 + packet_offset].packed.pressure1_L;
00663 break;
00664
00665 case 2:
00666 muscle_pressure =
00667 (status_data->muscle_data_packet[muscle_driver_id * 2 + packet_offset].packed.pressure2_H << 8)
00668 + (status_data->muscle_data_packet[muscle_driver_id * 2 + packet_offset].packed.pressure2_M << 4)
00669 + status_data->muscle_data_packet[muscle_driver_id * 2 + packet_offset].packed.pressure2_L;
00670 break;
00671
00672 case 3:
00673 muscle_pressure =
00674 (status_data->muscle_data_packet[muscle_driver_id * 2 + packet_offset].packed.pressure3_H << 8)
00675 + (status_data->muscle_data_packet[muscle_driver_id * 2 + packet_offset].packed.pressure3_M << 4)
00676 + status_data->muscle_data_packet[muscle_driver_id * 2 + packet_offset].packed.pressure3_L;
00677 break;
00678
00679 case 4:
00680 muscle_pressure =
00681 (status_data->muscle_data_packet[muscle_driver_id * 2 + packet_offset].packed.pressure4_H << 8)
00682 + (status_data->muscle_data_packet[muscle_driver_id * 2 + packet_offset].packed.pressure4_M << 4)
00683 + status_data->muscle_data_packet[muscle_driver_id * 2 + packet_offset].packed.pressure4_L;
00684 break;
00685
00686 default:
00687 ROS_ERROR("Incorrect muscle index: %d", muscle_index);
00688 break;
00689 }
00690
00691 return muscle_pressure;
00692 }
00693
00694 template<class StatusType, class CommandType>
00695 void SrMuscleRobotLib<StatusType, CommandType>::read_muscle_driver_data(
00696 vector<MuscleDriver>::iterator muscle_driver_tmp, StatusType *status_data)
00697 {
00698
00699
00700
00701 muscle_driver_tmp->driver_ok = sr_math_utils::is_bit_mask_index_true(status_data->which_muscle_data_arrived,
00702 muscle_driver_tmp->muscle_driver_id * 2);
00703
00704
00705
00706
00707
00708
00709
00710 if (muscle_driver_tmp->driver_ok)
00711 {
00712
00713 set_muscle_driver_data_received_flags(status_data->muscle_data_type, muscle_driver_tmp->muscle_driver_id);
00714
00715 switch (status_data->muscle_data_type)
00716 {
00717 case MUSCLE_DATA_PRESSURE:
00718
00719 break;
00720
00721 case MUSCLE_DATA_CAN_STATS:
00722
00723
00724
00725
00726 muscle_driver_tmp->can_msgs_received_ = sr_math_utils::counter_with_overflow(
00727 muscle_driver_tmp->can_msgs_received_,
00728 static_cast<int16u> (status_data->muscle_data_packet[muscle_driver_tmp->muscle_driver_id *
00729 2].misc.can_msgs_rx));
00730 muscle_driver_tmp->can_msgs_transmitted_ = sr_math_utils::counter_with_overflow(
00731 muscle_driver_tmp->can_msgs_transmitted_,
00732 static_cast<int16u> (status_data->muscle_data_packet[muscle_driver_tmp->muscle_driver_id *
00733 2].misc.can_msgs_tx));
00734
00735
00736 muscle_driver_tmp->can_err_rx = static_cast<unsigned int> (status_data->muscle_data_packet[
00737 muscle_driver_tmp->muscle_driver_id * 2].misc.can_err_rx);
00738 muscle_driver_tmp->can_err_tx = static_cast<unsigned int> (status_data->muscle_data_packet[
00739 muscle_driver_tmp->muscle_driver_id * 2].misc.can_err_tx);
00740 break;
00741
00742 case MUSCLE_DATA_SLOW_MISC:
00743
00744
00745
00746
00747
00748 muscle_driver_tmp->pic_firmware_git_revision_ = static_cast<unsigned int> (status_data->muscle_data_packet[
00749 muscle_driver_tmp->muscle_driver_id * 2].slow_0.SVN_revision);
00750 muscle_driver_tmp->server_firmware_git_revision_ = static_cast<unsigned int> (status_data->muscle_data_packet[
00751 muscle_driver_tmp->muscle_driver_id * 2].slow_0.SVN_server);
00752 muscle_driver_tmp->firmware_modified_ =
00753 static_cast<bool> (static_cast<unsigned int> (status_data->muscle_data_packet[
00754 muscle_driver_tmp->muscle_driver_id * 2].slow_0.SVN_modified));
00755
00756 muscle_driver_tmp->serial_number = static_cast<unsigned int> (status_data->muscle_data_packet[
00757 muscle_driver_tmp->muscle_driver_id * 2 + 1].slow_1.serial_number);
00758 muscle_driver_tmp->assembly_date_year = static_cast<unsigned int> (status_data->muscle_data_packet[
00759 muscle_driver_tmp->muscle_driver_id * 2 + 1].slow_1.assembly_date_YYYY);
00760 muscle_driver_tmp->assembly_date_month = static_cast<unsigned int> (status_data->muscle_data_packet[
00761 muscle_driver_tmp->muscle_driver_id * 2 + 1].slow_1.assembly_date_MM);
00762 muscle_driver_tmp->assembly_date_day = static_cast<unsigned int> (status_data->muscle_data_packet[
00763 muscle_driver_tmp->muscle_driver_id * 2 + 1].slow_1.assembly_date_DD);
00764 break;
00765
00766 default:
00767 break;
00768 }
00769
00770
00771 boost::mutex::scoped_lock l(*lock_init_timeout_);
00772
00773
00774 if (muscle_current_state == operation_mode::device_update_state::INITIALIZATION)
00775 {
00776 if ((check_muscle_driver_data_received_flags())
00777 || (muscle_updater_->update_state == operation_mode::device_update_state::OPERATION))
00778 {
00779 muscle_updater_->update_state = operation_mode::device_update_state::OPERATION;
00780 muscle_current_state = operation_mode::device_update_state::OPERATION;
00781
00782 check_init_timeout_timer.stop();
00783
00784 ROS_INFO("All muscle data initialized.");
00785 }
00786 }
00787 }
00788 }
00789
00790 template<class StatusType, class CommandType>
00791 inline void SrMuscleRobotLib<StatusType, CommandType>::set_muscle_driver_data_received_flags(unsigned int msg_type,
00792 int muscle_driver_id)
00793 {
00794 if (muscle_current_state == operation_mode::device_update_state::INITIALIZATION)
00795 {
00796 map<unsigned int, unsigned int>::iterator it = from_muscle_driver_data_received_flags_.find(msg_type);
00797 if (it != from_muscle_driver_data_received_flags_.end())
00798 {
00799 it->second = it->second | (1 << muscle_driver_id);
00800 }
00801 }
00802 }
00803
00804 template<class StatusType, class CommandType>
00805 inline bool SrMuscleRobotLib<StatusType, CommandType>::check_muscle_driver_data_received_flags()
00806 {
00807 map<unsigned int, unsigned int>::iterator it = from_muscle_driver_data_received_flags_.begin();
00808 for (; it != from_muscle_driver_data_received_flags_.end(); ++it)
00809 {
00810
00811
00812 if (it->second != (1 << NUM_MUSCLE_DRIVERS) - 1)
00813 {
00814 return false;
00815 }
00816 }
00817 return true;
00818 }
00819
00820 template<class StatusType, class CommandType>
00821 void SrMuscleRobotLib<StatusType, CommandType>::calibrate_joint(vector<Joint>::iterator joint_tmp,
00822 StatusType *status_data)
00823 {
00824 SrMuscleActuator *actuator = get_joint_actuator(joint_tmp);
00825
00826 actuator->muscle_state_.raw_sensor_values_.clear();
00827 actuator->muscle_state_.calibrated_sensor_values_.clear();
00828
00829 if (joint_tmp->joint_to_sensor.calibrate_after_combining_sensors)
00830 {
00831
00832
00833
00834 double raw_position = 0.0;
00835
00836
00837
00838 BOOST_FOREACH(PartialJointToSensor joint_to_sensor, joint_tmp->joint_to_sensor.joint_to_sensor_vector)
00839 {
00840 int tmp_raw = status_data->sensors[joint_to_sensor.sensor_id];
00841 actuator->muscle_state_.raw_sensor_values_.push_back(tmp_raw);
00842 raw_position += static_cast<double> (tmp_raw) * joint_to_sensor.coeff;
00843 }
00844
00845
00846 this->calibration_tmp = this->calibration_map.find(joint_tmp->joint_name);
00847 actuator->muscle_state_.position_unfiltered_ = this->calibration_tmp->compute(static_cast<double> (raw_position));
00848 }
00849 else
00850 {
00851
00852
00853 double calibrated_position = 0.0;
00854 PartialJointToSensor joint_to_sensor;
00855 string sensor_name;
00856
00857 ROS_DEBUG_STREAM("Combining actuator " << joint_tmp->joint_name);
00858
00859 for (unsigned int index_joint_to_sensor = 0;
00860 index_joint_to_sensor < joint_tmp->joint_to_sensor.joint_to_sensor_vector.size();
00861 ++index_joint_to_sensor)
00862 {
00863 joint_to_sensor = joint_tmp->joint_to_sensor.joint_to_sensor_vector[index_joint_to_sensor];
00864 sensor_name = joint_tmp->joint_to_sensor.sensor_names[index_joint_to_sensor];
00865
00866
00867 int raw_pos = status_data->sensors[joint_to_sensor.sensor_id];
00868
00869 actuator->muscle_state_.raw_sensor_values_.push_back(raw_pos);
00870
00871
00872 this->calibration_tmp = this->calibration_map.find(sensor_name);
00873 double tmp_cal_value = this->calibration_tmp->compute(static_cast<double> (raw_pos));
00874
00875
00876 actuator->muscle_state_.calibrated_sensor_values_.push_back(tmp_cal_value);
00877
00878 calibrated_position += tmp_cal_value * joint_to_sensor.coeff;
00879
00880 ROS_DEBUG_STREAM(" -> " << sensor_name << " raw = " << raw_pos << " calibrated = " << calibrated_position);
00881 }
00882 actuator->muscle_state_.position_unfiltered_ = calibrated_position;
00883 ROS_DEBUG_STREAM(" => " << actuator->muscle_state_.position_unfiltered_);
00884 }
00885 }
00886
00887 template<class StatusType, class CommandType>
00888 void SrMuscleRobotLib<StatusType, CommandType>::process_position_sensor_data(vector<Joint>::iterator joint_tmp,
00889 StatusType *status_data,
00890 double timestamp)
00891 {
00892 SrMuscleActuator *actuator = get_joint_actuator(joint_tmp);
00893
00894
00895 calibrate_joint(joint_tmp, status_data);
00896
00897
00898 pair<double, double> pos_and_velocity = joint_tmp->pos_filter.compute(actuator->muscle_state_.position_unfiltered_,
00899 timestamp);
00900
00901 actuator->state_.position_ = pos_and_velocity.first;
00902
00903 actuator->state_.velocity_ = pos_and_velocity.second;
00904 }
00905
00906 template<class StatusType, class CommandType>
00907 vector<pair<string, bool> > SrMuscleRobotLib<StatusType, CommandType>::humanize_flags(int flag)
00908 {
00909 vector<pair<string, bool> > flags;
00910
00911
00912 for (unsigned int i = 0; i < 16; ++i)
00913 {
00914 pair<string, bool> new_flag;
00915
00916 if (sr_math_utils::is_bit_mask_index_true(flag, i))
00917 {
00918 if (sr_math_utils::is_bit_mask_index_true(SERIOUS_ERROR_FLAGS, i))
00919 {
00920 new_flag.second = true;
00921 }
00922 else
00923 {
00924 new_flag.second = false;
00925 }
00926
00927 new_flag.first = error_flag_names[i];
00928 flags.push_back(new_flag);
00929 }
00930 }
00931 return flags;
00932 }
00933
00934 template<class StatusType, class CommandType>
00935 void SrMuscleRobotLib<StatusType, CommandType>::reinitialize_motors()
00936 {
00937
00938 boost::mutex::scoped_lock l(*lock_init_timeout_);
00939
00940
00941 check_init_timeout_timer.stop();
00942
00943 muscle_updater_ = shared_ptr<MuscleUpdater<CommandType> >(
00944 new MuscleUpdater<CommandType>(muscle_update_rate_configs_vector,
00945 operation_mode::device_update_state::INITIALIZATION));
00946 muscle_current_state = operation_mode::device_update_state::INITIALIZATION;
00947
00948 check_init_timeout_timer.setPeriod(init_max_duration);
00949 check_init_timeout_timer.start();
00950 }
00951
00952 template<class StatusType, class CommandType>
00953 void SrMuscleRobotLib<StatusType, CommandType>::init_timer_callback(const ros::TimerEvent &event)
00954 {
00955
00956 boost::mutex::scoped_lock l(*lock_init_timeout_);
00957
00958 if (muscle_current_state == operation_mode::device_update_state::INITIALIZATION)
00959 {
00960 muscle_updater_->update_state = operation_mode::device_update_state::OPERATION;
00961 muscle_current_state = operation_mode::device_update_state::OPERATION;
00962 ROS_ERROR_STREAM(
00963 "Muscle Initialization Timeout: the static information in the diagnostics may not be up to date.");
00964 }
00965 }
00966
00967
00968 template
00969 class SrMuscleRobotLib<ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND>;
00970 }
00971
00972
00973
00974
00975
00976