sr_muscle_hand_lib.cpp
Go to the documentation of this file.
00001 
00028 #include "sr_robot_lib/sr_muscle_hand_lib.hpp"
00029 #include <algorithm>
00030 #include <utility>
00031 #include <string>
00032 #include <vector>
00033 #include <boost/foreach.hpp>
00034 #include <boost/algorithm/string.hpp>
00035 
00036 #include <sr_utilities/sr_math_utils.hpp>
00037 
00038 #include "sr_robot_lib/shadow_PSTs.hpp"
00039 
00040 
00041 using std::vector;
00042 using std::string;
00043 using std::pair;
00044 using std::ostringstream;
00045 using sr_actuator::SrMuscleActuator;
00046 using shadow_joints::Joint;
00047 using shadow_joints::JointToSensor;
00048 using shadow_joints::JointToMuscle;
00049 using shadow_joints::MuscleWrapper;
00050 using shadow_joints::MuscleDriver;
00051 using shadow_joints::PartialJointToSensor;
00052 using generic_updater::MuscleUpdater;
00053 using boost::shared_ptr;
00054 using boost::static_pointer_cast;
00055 using boost::shared_ptr;
00056 
00057 namespace shadow_robot
00058 {
00059   template<class StatusType, class CommandType>
00060   const int SrMuscleHandLib<StatusType, CommandType>::nb_muscle_data = 3;
00061 
00062   template<class StatusType, class CommandType>
00063   const char *SrMuscleHandLib<StatusType, CommandType>::human_readable_muscle_data_types[nb_muscle_data] = {
00064           "muscle_data_pressure",
00065           "muscle_data_can_stats",
00066           "muscle_data_slow_misc"};
00067 
00068   template<class StatusType, class CommandType>
00069   const int32u SrMuscleHandLib<StatusType, CommandType>::muscle_data_types[nb_muscle_data] = {MUSCLE_DATA_PRESSURE,
00070                                                                                               MUSCLE_DATA_CAN_STATS,
00071                                                                                               MUSCLE_DATA_SLOW_MISC};
00072 
00073   template<class StatusType, class CommandType>
00074   SrMuscleHandLib<StatusType, CommandType>::SrMuscleHandLib(hardware_interface::HardwareInterface *hw,
00075                                                             ros::NodeHandle nh, ros::NodeHandle nhtilde,
00076                                                             string device_id, string joint_prefix) :
00077           SrMuscleRobotLib<StatusType, CommandType>(hw, nh, nhtilde, device_id, joint_prefix)
00078 #ifdef DEBUG_PUBLISHER
00079           // advertise the debug service, used to set which data we want to publish on the debug topics
00080           , debug_service(
00081           nh_tilde.advertiseService("set_debug_publishers", &SrMuscleHandLib::set_debug_data_to_publish, this))
00082 #endif
00083   {
00084     // read the muscle polling frequency from the parameter server
00085     this->muscle_update_rate_configs_vector = this->read_update_rate_configs("muscle_data_update_rate/", nb_muscle_data,
00086                                                                              human_readable_muscle_data_types,
00087                                                                              muscle_data_types);
00088     this->muscle_updater_ = shared_ptr<MuscleUpdater<CommandType> >(
00089             new MuscleUpdater<CommandType>(this->muscle_update_rate_configs_vector,
00090                                            operation_mode::device_update_state::INITIALIZATION));
00091 
00092     for (unsigned int i = 0; i < this->muscle_update_rate_configs_vector.size(); ++i)
00093     {
00094       // The initialization parameters (assigned a -2 in the config file)
00095       // are introduced in the flags map that will allow us to determine
00096       // if the data has been received from every muscle driver
00097       if (this->muscle_update_rate_configs_vector[i].when_to_update == -2)
00098       {
00099         this->from_muscle_driver_data_received_flags_[this->muscle_update_rate_configs_vector[i].what_to_update] = 0;
00100       }
00101     }
00102 
00103     for (unsigned int i = 0; i < NUM_MUSCLE_DRIVERS; ++i)
00104     {
00105       MuscleDriver driver(i);
00106 
00107       ostringstream ss;
00108       ss << "reset_muscle_driver_" << i;
00109       // initialize the reset muscle driver service
00110       driver.reset_driver_service =
00111               this->nh_tilde.template advertiseService<std_srvs::Empty::Request,
00112                       std_srvs::Empty::Response>(ss.str().c_str(),
00113                                                  boost::bind(
00114                                                          &SrMuscleHandLib<StatusType,
00115                                                                  CommandType>::reset_muscle_driver_callback,
00116                                                          this, _1, _2, i));
00117 
00118       this->muscle_drivers_vector_.push_back(driver);
00119     }
00120 
00121     vector<JointToSensor> joint_to_sensor_vect = this->read_joint_to_sensor_mapping();
00122 
00123     // initializing the joints vector
00124     vector<string> joint_names_tmp;
00125     vector<JointToMuscle> joint_to_muscle_map = read_joint_to_muscle_mapping();
00126     vector<JointToSensor> joints_to_sensors;
00127 
00128     ROS_ASSERT(joint_to_muscle_map.size() == JOINTS_NUM_0320);
00129     ROS_ASSERT(joint_to_sensor_vect.size() == JOINTS_NUM_0320);
00130 
00131     for (unsigned int i = 0; i < JOINTS_NUM_0320; ++i)
00132     {
00133       joint_names_tmp.push_back(string(joint_names[i]));
00134       JointToSensor tmp_jts = joint_to_sensor_vect[i];
00135       joints_to_sensors.push_back(tmp_jts);
00136     }
00137     initialize(joint_names_tmp, joint_to_muscle_map, joint_to_sensor_vect);
00138   }
00139 
00140   template<class StatusType, class CommandType>
00141   void SrMuscleHandLib<StatusType, CommandType>::initialize(vector<string> joint_names,
00142                                                             vector<int> actuator_ids,
00143                                                             vector<JointToSensor> joint_to_sensors)
00144   {
00145     ROS_ERROR("This version of SrMuscleHandLib<StatusType, CommandType>::initialize should not be used");
00146   }
00147 
00148   template<class StatusType, class CommandType>
00149   void SrMuscleHandLib<StatusType, CommandType>::initialize(vector<string> joint_names,
00150                                                             vector<JointToMuscle> actuator_ids,
00151                                                             vector<JointToSensor> joint_to_sensors)
00152   {
00153     for (unsigned int index = 0; index < joint_names.size(); ++index)
00154     {
00155       // add the joint and the vector of joints.
00156       Joint joint;
00157 
00158       // update the joint variables
00159       joint.joint_name = joint_names[index];
00160       joint.joint_to_sensor = joint_to_sensors[index];
00161 
00162       if (actuator_ids[index].muscle_driver_id[0] != -1)
00163       {
00164         joint.has_actuator = true;
00165         shared_ptr<MuscleWrapper> muscle_wrapper(new MuscleWrapper());
00166         joint.actuator_wrapper = muscle_wrapper;
00167         muscle_wrapper->muscle_driver_id[0] = actuator_ids[index].muscle_driver_id[0];
00168         muscle_wrapper->muscle_driver_id[1] = actuator_ids[index].muscle_driver_id[1];
00169         muscle_wrapper->muscle_id[0] = actuator_ids[index].muscle_id[0];
00170         muscle_wrapper->muscle_id[1] = actuator_ids[index].muscle_id[1];
00171         muscle_wrapper->actuator = static_cast<SrMuscleActuator *> (this->hw_->getActuator(
00172                 this->joint_prefix_ + joint.joint_name));
00173       }
00174       else
00175       { // no muscles associated to this joint. We only check the driver 0 assuming
00176         // a joint with -1 will have -1 in the driver 1 as well
00177         joint.has_actuator = false;
00178       }
00179 
00180       this->joints_vector.push_back(joint);
00181     }  // end for joints.
00182   }
00183 
00184   template<class StatusType, class CommandType>
00185   bool SrMuscleHandLib<StatusType, CommandType>::reset_muscle_driver_callback(std_srvs::Empty::Request &request,
00186                                                                               std_srvs::Empty::Response &response,
00187                                                                               int muscle_driver_index)
00188   {
00189     ROS_INFO_STREAM(" resetting muscle driver " << muscle_driver_index);
00190 
00191     this->reset_muscle_driver_queue.push(muscle_driver_index);
00192 
00193     return true;
00194   }
00195 
00196   template<class StatusType, class CommandType>
00197   vector<JointToMuscle> SrMuscleHandLib<StatusType, CommandType>::read_joint_to_muscle_mapping()
00198   {
00199     vector<JointToMuscle> muscle_map;
00200     string param_name = "joint_to_muscle_mapping";
00201 
00202     XmlRpc::XmlRpcValue mapping;
00203     this->nodehandle_.getParam(param_name, mapping);
00204     ROS_ASSERT(mapping.getType() == XmlRpc::XmlRpcValue::TypeArray);
00205     // iterate on all the joints
00206     for (int32_t i = 0; i < mapping.size(); ++i)
00207     {
00208       ROS_ASSERT(mapping[i].getType() == XmlRpc::XmlRpcValue::TypeArray);
00209 
00210       ROS_ASSERT(mapping[i][0].getType() == XmlRpc::XmlRpcValue::TypeArray);
00211       ROS_ASSERT(mapping[i][0][0].getType() == XmlRpc::XmlRpcValue::TypeInt);
00212       ROS_ASSERT(mapping[i][0][1].getType() == XmlRpc::XmlRpcValue::TypeInt);
00213 
00214       ROS_ASSERT(mapping[i][1].getType() == XmlRpc::XmlRpcValue::TypeArray);
00215       ROS_ASSERT(mapping[i][1][0].getType() == XmlRpc::XmlRpcValue::TypeInt);
00216       ROS_ASSERT(mapping[i][1][1].getType() == XmlRpc::XmlRpcValue::TypeInt);
00217 
00218       JointToMuscle joint_to_muscle;
00219 
00220       joint_to_muscle.muscle_driver_id[0] = mapping[i][0][0];
00221       joint_to_muscle.muscle_id[0] = mapping[i][0][1];
00222       joint_to_muscle.muscle_driver_id[1] = mapping[i][1][0];
00223       joint_to_muscle.muscle_id[1] = mapping[i][1][1];
00224 
00225       muscle_map.push_back(joint_to_muscle);
00226     }
00227 
00228     return muscle_map;
00229   }  // end read_joint_to_muscle_mapping
00230 
00231 #ifdef DEBUG_PUBLISHER
00232   template <class StatusType, class CommandType>
00233   bool SrMuscleHandLib<StatusType,
00234           CommandType>::set_debug_data_to_publish(sr_robot_msgs::SetDebugData::Request& request,
00235                                                   sr_robot_msgs::SetDebugData::Response& response)
00236   {
00237     // check if the publisher_index is correct
00238     if (request.publisher_index < this->nb_debug_publishers_const)
00239     {
00240       if (request.motor_index > NUM_MOTORS)
00241       {
00242         response.success = false;
00243         return false;
00244       }
00245       if (request.motor_data_type > 0)
00246       {
00247         if ((request.motor_data_type < MOTOR_DATA_SGL) ||
00248             (request.motor_data_type > MOTOR_DATA_DTERM))
00249         {
00250           response.success = false;
00251           return false;
00252         }
00253       }
00254       if (!this->debug_mutex.timed_lock(boost::posix_time::microseconds(this->debug_mutex_lock_wait_time)))
00255       {
00256         response.success = false;
00257         return false;
00258       }
00259 
00260       this->debug_motor_indexes_and_data[request.publisher_index] = shared_ptr<pair<int, int> >(new pair<int, int>());
00261 
00262       this->debug_motor_indexes_and_data[request.publisher_index]->first = request.motor_index;
00263       this->debug_motor_indexes_and_data[request.publisher_index]->second = request.motor_data_type;
00264       this->debug_mutex.unlock();
00265     }
00266     else
00267     {
00268       response.success = false;
00269       return false;
00270     }
00271 
00272     response.success = true;
00273     return true;
00274   }
00275 #endif
00276 
00277   // Only to ensure that the template class is compiled for the types we are interested in
00278   template
00279   class SrMuscleHandLib<ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND>;
00280 }  // namespace shadow_robot
00281 
00282 /* For the emacs weenies in the crowd.
00283 Local Variables:
00284    c-basic-offset: 2
00285 End:
00286  */


sr_robot_lib
Author(s): Ugo Cupcic, Toni Oliver
autogenerated on Mon Jul 1 2019 20:06:26