Go to the documentation of this file.00001
00027 #include "sr_hand/hand/etherCAT_compatibility_hand.hpp"
00028 #include <sr_utilities/sr_math_utils.hpp>
00029
00030 #include <time.h>
00031 #include <ros/ros.h>
00032 #include <ros/topic.h>
00033 #include <std_msgs/Float64.h>
00034 #include <control_msgs/JointControllerState.h>
00035 #include <sr_robot_msgs/JointControllerState.h>
00036
00037 namespace shadowrobot
00038 {
00039 ROS_DEPRECATED EtherCATCompatibilityHand::EtherCATCompatibilityHand() :
00040 SRArticulatedRobot(), n_tilde("~")
00041 {
00042 ROS_WARN("This interface is deprecated, you should probably use the interface provided by the etherCAT driver directly.");
00043
00044 initializeMap();
00045
00046 joint_state_subscriber = node.subscribe("/joint_states", 2, &EtherCATCompatibilityHand::joint_states_callback, this);
00047
00048 }
00049
00050 EtherCATCompatibilityHand::~EtherCATCompatibilityHand()
00051 {
00052 }
00053
00054 void EtherCATCompatibilityHand::initializeMap()
00055 {
00056 joints_map_mutex.lock();
00057 JointData tmpData;
00058 JointData tmpDataZero;
00059 tmpDataZero.isJointZero = 1;
00060 tmpDataZero.max = 180.0;
00061 tmpData.max=90.0;
00062
00063 std::string full_topic = "";
00064
00065 full_topic = findControllerTopicName("ffj0");
00066 etherCAT_publishers.push_back(node.advertise<std_msgs::Float64>(full_topic, 2));
00067 int tmp_index = 0;
00068 tmpDataZero.publisher_index = tmp_index;
00069 joints_map["FFJ0"] = tmpDataZero;
00070 joints_map["FFJ1"] = tmpData;
00071 joints_map["FFJ2"] = tmpData;
00072
00073 full_topic = findControllerTopicName("ffj3");
00074 etherCAT_publishers.push_back(node.advertise<std_msgs::Float64>(full_topic, 2));
00075 tmp_index ++;
00076 tmpData.publisher_index = tmp_index;
00077 joints_map["FFJ3"] = tmpData;
00078
00079 tmpData.min = -20.0;
00080 tmpData.max = 20.0;
00081 full_topic = findControllerTopicName("ffj4");
00082 etherCAT_publishers.push_back(node.advertise<std_msgs::Float64>(full_topic, 2));
00083 tmp_index ++;
00084 tmpData.publisher_index = tmp_index;
00085 joints_map["FFJ4"] = tmpData;
00086
00087 full_topic = findControllerTopicName("mfj0");
00088 etherCAT_publishers.push_back(node.advertise<std_msgs::Float64>(full_topic, 2));
00089 tmp_index ++;
00090 tmpDataZero.publisher_index = tmp_index;
00091 joints_map["MFJ0"] = tmpDataZero;
00092
00093 tmpData.min = 0.0;
00094 tmpData.max = 90.0;
00095 joints_map["MFJ1"] = tmpData;
00096 joints_map["MFJ2"] = tmpData;
00097
00098 full_topic = findControllerTopicName("mfj3");
00099 etherCAT_publishers.push_back(node.advertise<std_msgs::Float64>(full_topic, 2));
00100 tmp_index ++;
00101 tmpData.publisher_index = tmp_index;
00102 joints_map["MFJ3"] = tmpData;
00103
00104 tmpData.min = -20.0;
00105 tmpData.max = 20.0;
00106 full_topic = findControllerTopicName("mfj4");
00107 etherCAT_publishers.push_back(node.advertise<std_msgs::Float64>(full_topic, 2));
00108 tmp_index ++;
00109 tmpData.publisher_index = tmp_index;
00110 joints_map["MFJ4"] = tmpData;
00111
00112 full_topic = findControllerTopicName("rfj0");
00113 etherCAT_publishers.push_back(node.advertise<std_msgs::Float64>(full_topic, 2));
00114 tmp_index ++;
00115 tmpDataZero.publisher_index = tmp_index;
00116 joints_map["RFJ0"] = tmpDataZero;
00117
00118 tmpData.min = 0.0;
00119 tmpData.max = 90.0;
00120 joints_map["RFJ1"] = tmpData;
00121 joints_map["RFJ2"] = tmpData;
00122 full_topic = findControllerTopicName("rfj3");
00123 etherCAT_publishers.push_back(node.advertise<std_msgs::Float64>(full_topic, 2));
00124 tmp_index ++;
00125 tmpData.publisher_index = tmp_index;
00126 joints_map["RFJ3"] = tmpData;
00127
00128 tmpData.min = -20.0;
00129 tmpData.max = 20.0;
00130 full_topic = findControllerTopicName("rfj4");
00131 etherCAT_publishers.push_back(node.advertise<std_msgs::Float64>(full_topic, 2));
00132 tmp_index ++;
00133 tmpData.publisher_index = tmp_index;
00134 joints_map["RFJ4"] = tmpData;
00135
00136 full_topic = findControllerTopicName("lfj0");
00137 etherCAT_publishers.push_back(node.advertise<std_msgs::Float64>(full_topic, 2));
00138 tmp_index ++;
00139 tmpDataZero.publisher_index = tmp_index;
00140 joints_map["LFJ0"] = tmpDataZero;
00141
00142 tmpData.min = 0.0;
00143 tmpData.max = 90.0;
00144 joints_map["LFJ1"] = tmpData;
00145 joints_map["LFJ2"] = tmpData;
00146
00147 full_topic = findControllerTopicName("lfj3");
00148 etherCAT_publishers.push_back(node.advertise<std_msgs::Float64>(full_topic, 2));
00149 tmp_index ++;
00150 tmpData.publisher_index = tmp_index;
00151 joints_map["LFJ3"] = tmpData;
00152
00153 tmpData.min = -20.0;
00154 tmpData.max = 20.0;
00155 full_topic = findControllerTopicName("lfj4");
00156 etherCAT_publishers.push_back(node.advertise<std_msgs::Float64>(full_topic, 2));
00157 tmp_index ++;
00158 tmpData.publisher_index = tmp_index;
00159 joints_map["LFJ4"] = tmpData;
00160
00161 tmpData.min = 0.0;
00162 tmpData.max = 45.0;
00163 full_topic = findControllerTopicName("lfj5");
00164 etherCAT_publishers.push_back(node.advertise<std_msgs::Float64>(full_topic, 2));
00165 tmp_index ++;
00166 tmpData.publisher_index = tmp_index;
00167 joints_map["LFJ5"] = tmpData;
00168
00169 tmpData.min = 0.0;
00170 tmpData.max = 90.0;
00171 full_topic = findControllerTopicName("thj1");
00172 etherCAT_publishers.push_back(node.advertise<std_msgs::Float64>(full_topic, 2));
00173 tmp_index ++;
00174 tmpData.publisher_index = tmp_index;
00175 joints_map["THJ1"] = tmpData;
00176
00177 tmpData.min = -40.0;
00178 tmpData.max = 40.0;
00179 full_topic = findControllerTopicName("thj2");
00180 etherCAT_publishers.push_back(node.advertise<std_msgs::Float64>(full_topic, 2));
00181 tmp_index ++;
00182 tmpData.publisher_index = tmp_index;
00183 joints_map["THJ2"] = tmpData;
00184
00185 tmpData.min = -15.0;
00186 tmpData.max = 15.0;
00187 full_topic = findControllerTopicName("thj3");
00188 etherCAT_publishers.push_back(node.advertise<std_msgs::Float64>(full_topic, 2));
00189 tmp_index ++;
00190 tmpData.publisher_index = tmp_index;
00191 joints_map["THJ3"] = tmpData;
00192
00193 tmpData.min = 0.0;
00194 tmpData.max = 75.0;
00195 full_topic = findControllerTopicName("thj4");
00196 etherCAT_publishers.push_back(node.advertise<std_msgs::Float64>(full_topic, 2));
00197 tmp_index ++;
00198 tmpData.publisher_index = tmp_index;
00199 joints_map["THJ4"] = tmpData;
00200
00201 tmpData.min = -60.0;
00202 tmpData.max = 60.0;
00203 full_topic = findControllerTopicName("thj5");
00204 etherCAT_publishers.push_back(node.advertise<std_msgs::Float64>(full_topic, 2));
00205 tmp_index ++;
00206 tmpData.publisher_index = tmp_index;
00207 joints_map["THJ5"] = tmpData;
00208
00209 tmpData.min = -30.0;
00210 tmpData.max = 45.0;
00211 full_topic = findControllerTopicName("wrj1");
00212 etherCAT_publishers.push_back(node.advertise<std_msgs::Float64>(full_topic, 2));
00213 tmp_index ++;
00214 tmpData.publisher_index = tmp_index;
00215 joints_map["WRJ1"] = tmpData;
00216
00217 tmpData.min = -30.0;
00218 tmpData.max = 10.0;
00219 full_topic = findControllerTopicName("wrj2");
00220 etherCAT_publishers.push_back(node.advertise<std_msgs::Float64>(full_topic, 2));
00221 tmp_index ++;
00222 tmpData.publisher_index = tmp_index;
00223 joints_map["WRJ2"] = tmpData;
00224
00225 joints_map_mutex.unlock();
00226 }
00227
00228 std::string EtherCATCompatibilityHand::findControllerTopicName( std::string joint_name)
00229 {
00230 std::string joint_prefix;
00231 n_tilde.param("joint_prefix", joint_prefix, std::string(""));
00232
00233
00234 std::string controller_suffix = "position_controller";
00235
00236 std::string searched_param;
00237 n_tilde.searchParam("controller_suffix", searched_param);
00238 n_tilde.param(searched_param, controller_suffix, std::string("position_controller"));
00239
00240 std::string topic_prefix = "/sh_";
00241 std::string topic_suffix = "_" + controller_suffix + "/command";
00242 std::string full_topic = topic_prefix + joint_prefix + joint_name + topic_suffix;
00243
00244 return full_topic;
00245 }
00246
00247 short EtherCATCompatibilityHand::sendupdate( std::string joint_name, double target )
00248 {
00249 if( !joints_map_mutex.try_lock() )
00250 return -1;
00251 JointsMap::iterator iter = joints_map.find(joint_name);
00252 std_msgs::Float64 target_msg;
00253
00254
00255 if( iter == joints_map.end() )
00256 {
00257 ROS_DEBUG("Joint %s not found", joint_name.c_str());
00258
00259 joints_map_mutex.unlock();
00260 return -1;
00261 }
00262
00263
00264 JointData tmpData(iter->second);
00265
00266 if( target < tmpData.min )
00267 target = tmpData.min;
00268 if( target > tmpData.max )
00269 target = tmpData.max;
00270
00271 tmpData.target = target;
00272
00273 joints_map[joint_name] = tmpData;
00274
00275 target_msg.data = sr_math_utils::to_rad( target );
00276
00277
00278 etherCAT_publishers[tmpData.publisher_index].publish(target_msg);
00279
00280 joints_map_mutex.unlock();
00281 return 0;
00282 }
00283
00284 JointData EtherCATCompatibilityHand::getJointData( std::string joint_name )
00285 {
00286 JointData noData;
00287 if( !joints_map_mutex.try_lock() )
00288 return noData;
00289
00290 JointsMap::iterator iter = joints_map.find(joint_name);
00291
00292
00293 if( iter != joints_map.end() )
00294 {
00295 JointData tmp = JointData(iter->second);
00296
00297 joints_map_mutex.unlock();
00298 return tmp;
00299 }
00300
00301 ROS_ERROR("Joint %s not found.", joint_name.c_str());
00302 joints_map_mutex.unlock();
00303 return noData;
00304 }
00305
00306 SRArticulatedRobot::JointsMap EtherCATCompatibilityHand::getAllJointsData()
00307 {
00308 return joints_map;
00309 }
00310
00311 short EtherCATCompatibilityHand::setContrl( std::string contrlr_name, JointControllerData ctrlr_data )
00312 {
00313 ROS_WARN("The set Controller function is not implemented in the EtherCAT compatibility wrapper, please use the provided services directly.");
00314 return 0;
00315 }
00316
00317 JointControllerData EtherCATCompatibilityHand::getContrl( std::string contrlr_name )
00318 {
00319 JointControllerData no_result;
00320 ROS_WARN("The get Controller function is not implemented in the EtherCAT compatibility wrapper, please use the provided services directly.");
00321 return no_result;
00322 }
00323
00324 short EtherCATCompatibilityHand::setConfig( std::vector<std::string> myConfig )
00325 {
00326 ROS_WARN("The set config function is not implemented.");
00327 return 0;
00328 }
00329
00330 void EtherCATCompatibilityHand::getConfig( std::string joint_name )
00331 {
00332 ROS_WARN("The get config function is not implemented.");
00333 }
00334
00335 std::vector<DiagnosticData> EtherCATCompatibilityHand::getDiagnostics()
00336 {
00337 std::vector<DiagnosticData> returnVect;
00338 return returnVect;
00339 }
00340
00341 void EtherCATCompatibilityHand::joint_states_callback(const sensor_msgs::JointStateConstPtr& msg)
00342 {
00343 if( !joints_map_mutex.try_lock() )
00344 return;
00345 std::string fj0char;
00346 bool fj0flag=false;
00347 double fj0pos,fj0vel,fj0eff;
00348
00349 for(unsigned int index = 0; index < msg->name.size(); ++index)
00350 {
00351 std::string joint_name = msg->name[index];
00352 JointsMap::iterator iter = joints_map.find(joint_name);
00353
00354
00355 if(iter == joints_map.end())
00356 {
00357 continue;
00358 }
00359 else
00360 {
00361
00362 if( joint_name.find("FJ1")!=std::string::npos)
00363 {
00364
00365 if(fj0flag && joint_name[0]==fj0char[0])
00366 {
00367 std::string j0name=fj0char+"FJ0";
00368 JointsMap::iterator myiter = joints_map.find(j0name);
00369 if(myiter == joints_map.end())
00370 continue;
00371 else
00372 {
00373 JointData tmpDatazero(myiter->second);
00374 tmpDatazero.position = fj0pos+ sr_math_utils::to_degrees(msg->position[index]);
00375 tmpDatazero.velocity = fj0vel + msg->effort[index];
00376 tmpDatazero.force = fj0eff + msg->velocity[index];
00377 joints_map[j0name] = tmpDatazero;
00378
00379 fj0pos=0;
00380 fj0vel=0;
00381 fj0eff=0;
00382 fj0char.clear();
00383 fj0flag=false;
00384 }
00385 }
00386 else
00387 {
00388 fj0pos=sr_math_utils::to_degrees(msg->position[index]);
00389 fj0eff=msg->effort[index];
00390 fj0vel=msg->velocity[index];
00391 fj0char.push_back(joint_name[0]);
00392 fj0flag=true;
00393
00394 }
00395 }
00396 else if( joint_name.find("FJ2")!=std::string::npos)
00397 {
00398
00399 if(fj0flag && joint_name[0]==fj0char[0])
00400 {
00401 std::string j0name=fj0char+"FJ0";
00402 JointsMap::iterator myiter = joints_map.find(j0name);
00403 if(myiter == joints_map.end())
00404 continue;
00405 else
00406 {
00407 JointData tmpDatazero(myiter->second);
00408 tmpDatazero.position = fj0pos+ sr_math_utils::to_degrees(msg->position[index]);
00409 tmpDatazero.force = fj0vel + msg->effort[index];
00410 tmpDatazero.velocity = fj0eff + msg->velocity[index];
00411 joints_map[j0name] = tmpDatazero;
00412
00413 fj0pos=0;
00414 fj0vel=0;
00415 fj0eff=0;
00416 fj0char.clear();
00417 fj0flag=false;
00418 }
00419 }
00420 else
00421 {
00422 fj0pos=sr_math_utils::to_degrees(msg->position[index]);
00423 fj0eff=msg->effort[index];
00424 fj0vel=msg->velocity[index];
00425 fj0char.push_back(joint_name[0]);
00426 fj0flag=true;
00427
00428 }
00429 }
00430
00431 JointData tmpData(iter->second);
00432 tmpData.position = sr_math_utils::to_degrees(msg->position[index]);
00433 tmpData.force = msg->effort[index];
00434 tmpData.velocity = msg->velocity[index];
00435 joints_map[joint_name] = tmpData;
00436 }
00437
00438 }
00439
00440 joints_map_mutex.unlock();
00441 }
00442
00443 }
00444
00445
00446
00447
00448
00449
00450