Go to the documentation of this file.00001
00030 #include <sr_hand/hand_commander.hpp>
00031 #include <pr2_mechanism_msgs/ListControllers.h>
00032 #include <sr_robot_msgs/sendupdate.h>
00033 #include <std_msgs/Float64.h>
00034 #include <boost/algorithm/string.hpp>
00035
00036 namespace shadowrobot
00037 {
00038
00039 const double HandCommander::TIMEOUT_TO_DETECT_CONTROLLER_MANAGER = 3.0;
00040
00041 HandCommander::HandCommander():
00042 hand_type(shadowhandRosLib::UNKNOWN),
00043 ethercat_controllers_found(false)
00044 {
00045
00046
00047 std::string robot_desc_string;
00048 node_.param("sh_description", robot_desc_string, std::string());
00049 urdf::Model robot_model;
00050 if (!robot_model.initString(robot_desc_string))
00051 {
00052 ROS_WARN("Failed to parse urdf file - trying with robot_description instead of sh_description.");
00053
00054 node_.param("robot_description", robot_desc_string, std::string());
00055 if (!robot_model.initString(robot_desc_string))
00056 {
00057 ROS_ERROR("Couldn't parse the urdf file on sh_description or on robot_description.");
00058 return;
00059 }
00060 }
00061
00062 all_joints = robot_model.joints_;
00063
00064
00065 if(ros::service::waitForService("pr2_controller_manager/list_controllers", ros::Duration(TIMEOUT_TO_DETECT_CONTROLLER_MANAGER)))
00066 {
00067 hand_type = shadowhandRosLib::ETHERCAT;
00068 initializeEthercatHand();
00069 ROS_INFO("HandCommander library: ETHERCAT hand detected");
00070 }
00071 else
00072 {
00073 hand_type = shadowhandRosLib::CAN;
00074 sr_hand_target_pub = node_.advertise<sr_robot_msgs::sendupdate>("srh/sendupdate", 2);
00075 ROS_INFO("HandCommander library: CAN hand detected");
00076 }
00077 }
00078
00079 HandCommander::~HandCommander()
00080 {
00081 }
00082
00083 void HandCommander::initializeEthercatHand()
00084 {
00085 sr_hand_target_pub_map.clear();
00086
00087 ros::ServiceClient controller_list_client = node_.serviceClient<pr2_mechanism_msgs::ListControllers>("pr2_controller_manager/list_controllers");
00088
00089 pr2_mechanism_msgs::ListControllers controller_list;
00090 std::string controlled_joint_name;
00091
00092 controller_list_client.call(controller_list);
00093 for (size_t i=0;i<controller_list.response.controllers.size() ;i++ )
00094 {
00095 if(controller_list.response.state[i]=="running")
00096 {
00097 std::string controller = controller_list.response.controllers[i];
00098 if (node_.getParam(controller+"/joint", controlled_joint_name))
00099 {
00100 ROS_DEBUG("controller %d:%s controls joint %s\n",
00101 (int)i,controller.c_str(),controlled_joint_name.c_str());
00102 sr_hand_target_pub_map[controlled_joint_name]
00103 = node_.advertise<std_msgs::Float64>(controller+"/command", 2);
00104 ethercat_controllers_found = true;
00105 sr_hand_sub_topics[controlled_joint_name] = controller+"/state";
00106 }
00107 }
00108 }
00109 }
00110
00111 void HandCommander::sendCommands(std::vector<sr_robot_msgs::joint> joint_vector)
00112 {
00113 if(hand_type == shadowhandRosLib::ETHERCAT)
00114 {
00115 if(!ethercat_controllers_found)
00116 {
00117 initializeEthercatHand();
00118
00119 if (!ethercat_controllers_found)
00120 return;
00121 }
00122 for(size_t i = 0; i < joint_vector.size(); ++i)
00123 {
00124 boost::algorithm::to_upper(joint_vector.at(i).joint_name);
00125 std_msgs::Float64 target;
00126 target.data = joint_vector.at(i).joint_target * M_PI/180.0;
00127 sr_hand_target_pub_map[joint_vector.at(i).joint_name].publish(target);
00128 }
00129 }
00130 else
00131 {
00132 sr_robot_msgs::sendupdate sendupdate_msg;
00133 sendupdate_msg.sendupdate_length = joint_vector.size();
00134 sendupdate_msg.sendupdate_list = joint_vector;
00135
00136 sr_hand_target_pub.publish(sendupdate_msg);
00137 }
00138 }
00139
00140 std::pair<double, double> HandCommander::get_min_max(std::string joint_name)
00141 {
00142
00143 std::vector<std::string> joint_names, split_name;
00144 boost::split( split_name, joint_name, boost::is_any_of("0") );
00145 if( split_name.size() == 1)
00146 {
00147
00148 joint_names.push_back(joint_name);
00149 }
00150 else
00151 {
00152
00153 joint_names.push_back(split_name[0] + "1");
00154 joint_names.push_back(split_name[0] + "2");
00155 }
00156
00157
00158 std::pair<double, double> min_max;
00159 for( size_t i = 0; i < joint_names.size(); ++i)
00160 {
00161 std::string jn = joint_names[i];
00162
00163
00164 boost::algorithm::to_upper(jn);
00165 std::map<std::string, boost::shared_ptr<urdf::Joint> >::iterator it = all_joints.find(jn);
00166
00167 if( it != all_joints.end() )
00168 {
00169 min_max.first += it->second->limits->lower;
00170 min_max.second += it->second->limits->upper;
00171 }
00172 else
00173 {
00174 ROS_ERROR_STREAM("Joint " << jn << " not found in the urdf description.");
00175 }
00176 }
00177
00178 return min_max;
00179 }
00180
00181 std::vector<std::string> HandCommander::get_all_joints()
00182 {
00183 std::vector<std::string> all_joints_names;
00184 std::map<std::string, std::string>::iterator it = sr_hand_sub_topics.begin();
00185
00186 for( it; it != sr_hand_sub_topics.end(); ++it )
00187 {
00188
00189
00190
00191 if(it->first.size() == 4)
00192 all_joints_names.push_back(it->first);
00193 }
00194
00195 return all_joints_names;
00196 }
00197
00198 std::string HandCommander::get_controller_state_topic(std::string joint_name)
00199 {
00200 std::string topic;
00201
00202 if(hand_type == shadowhandRosLib::ETHERCAT)
00203 {
00204
00205 boost::algorithm::to_upper(joint_name);
00206 std::map<std::string, std::string>::iterator it = sr_hand_sub_topics.find(joint_name);
00207 if( it != sr_hand_sub_topics.end() )
00208 {
00209 topic = it->second;
00210 }
00211 else
00212 {
00213 ROS_ERROR_STREAM(" Controller for joint " << joint_name << " not found.");
00214 }
00215 }
00216 else
00217 {
00218 topic = "shadowhand_data";
00219 }
00220
00221 return topic;
00222 }
00223 }
00224
00225
00226
00227
00228
00229