$search
00001 /* 00002 * UOS-ROS packages - Robot Operating System code by the University of Osnabrück 00003 * Copyright (C) 2011 University of Osnabrück 00004 * 00005 * This program is free software; you can redistribute it and/or 00006 * modify it under the terms of the GNU General Public License 00007 * as published by the Free Software Foundation; either version 2 00008 * of the License, or (at your option) any later version. 00009 * 00010 * This program is distributed in the hope that it will be useful, 00011 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00012 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00013 * GNU General Public License for more details. 00014 * 00015 * You should have received a copy of the GNU General Public License 00016 * along with this program; if not, write to the Free Software 00017 * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA. 00018 * 00019 * 00020 * katana_kinematics_plugin.cpp 00021 * based on the pr2_arm_kinematics_plugin.cpp by Sachin Chitta 00022 * 00023 * Created on: 30.05.2010 00024 * Author: Henning Deeken // hdeeken@uos.de 00025 */ 00026 00027 #include <katana_kinematics_constraint_aware/katana_openrave_kinematics.h> 00028 #include <pluginlib/class_list_macros.h> 00029 00030 using namespace tf; 00031 using namespace kinematics; 00032 using namespace std; 00033 using namespace ros; 00034 00035 // register KatanaKinematics as a KinematicsBase implementation 00036 PLUGINLIB_DECLARE_CLASS(katana_kinematics_constraint_aware, KatanaKinematicsPlugin, katana_kinematics_constraint_aware::KatanaKinematicsPlugin, kinematics::KinematicsBase) 00037 00038 namespace katana_kinematics_constraint_aware 00039 { 00040 00041 KatanaKinematicsPlugin::KatanaKinematicsPlugin() : 00042 active_(false) 00043 { 00044 } 00045 00046 bool KatanaKinematicsPlugin::isActive() 00047 { 00048 if (active_) 00049 return true; 00050 return false; 00051 } 00052 00053 bool KatanaKinematicsPlugin::initialize(std::string name) 00054 { 00055 urdf::Model robot_model; 00056 std::string tip_name, xml_string; 00057 ros::NodeHandle private_handle("~/" + name); 00058 00059 dimension_ = 5; 00060 00061 while (!arm_kinematics_constraint_aware::loadRobotModel(private_handle, robot_model, root_name_, tip_name, xml_string) 00062 && private_handle.ok()) 00063 { 00064 ROS_ERROR("Could not load robot model. Are you sure the robot model is on the parameter server?"); 00065 ros::Duration(0.5).sleep(); 00066 } 00067 00068 kinematics_msgs::KinematicSolverInfo kinematic_info; 00069 00070 if (!arm_kinematics_constraint_aware::getChainInfoFromRobotModel(robot_model, root_name_, tip_name, kinematic_info)) 00071 { 00072 ROS_FATAL("Could not get chain info!"); 00073 } 00074 00075 // connecting to services 00076 std::string fk_service; 00077 private_handle.param<std::string> ("fk_service", fk_service, "get_fk"); 00078 fk_service_ = node_handle_.serviceClient<kinematics_msgs::GetPositionFK> (fk_service); 00079 00080 std::string fk_info; 00081 private_handle.param<std::string> ("fk_info", fk_info, "get_fk_solver_info"); 00082 fk_solver_info_service_ = node_handle_.serviceClient<kinematics_msgs::GetKinematicSolverInfo> (fk_info); 00083 00084 std::string ik_service; 00085 private_handle.param<std::string> ("ik_service", ik_service, "IK"); 00086 ik_service_ = node_handle_.serviceClient<orrosplanning::IK> (ik_service); 00087 00088 if (!ros::service::waitForService(fk_info)) 00089 { 00090 ROS_ERROR("Could not load fk info"); 00091 active_ = false; 00092 } 00093 00094 if (!ros::service::waitForService(fk_service)) 00095 { 00096 ROS_ERROR("Could not load fk"); 00097 active_ = false; 00098 } 00099 00100 if (!ros::service::waitForService(ik_service)) 00101 { 00102 ROS_ERROR("Could not load ik"); 00103 active_ = false; 00104 } 00105 else 00106 { 00107 fk_solver_info_ = kinematic_info; 00108 ik_solver_info_ = fk_solver_info_; 00109 00110 for (unsigned int i = 0; i < fk_solver_info_.joint_names.size(); i++) 00111 { 00112 ROS_INFO("KatanaKinematics:: joint name: %s",fk_solver_info_.joint_names[i].c_str()); 00113 } 00114 for (unsigned int i = 0; i < ik_solver_info_.link_names.size(); i++) 00115 { 00116 ROS_INFO("KatanaKinematics can solve IK for %s",ik_solver_info_.link_names[i].c_str()); 00117 } 00118 for (unsigned int i = 0; i < fk_solver_info_.link_names.size(); i++) 00119 { 00120 ROS_INFO("KatanaKinematics can solve FK for %s",fk_solver_info_.link_names[i].c_str()); 00121 } 00122 ROS_INFO("KatanaKinematicsPlugin::active for %s",name.c_str()); 00123 active_ = true; 00124 } 00125 00126 ROS_DEBUG("Initializing the KatanaKinematicsPlugin was successful."); 00127 00128 return active_; 00129 } 00130 00131 bool KatanaKinematicsPlugin::getPositionIK(const geometry_msgs::Pose &ik_pose, 00132 const std::vector<double> &ik_seed_state, std::vector<double> &solution, 00133 int &error_code) 00134 { 00135 if (!active_) 00136 { 00137 ROS_ERROR("kinematics not active"); 00138 error_code = kinematics::SUCCESS; 00139 return false; 00140 } 00141 00142 ROS_DEBUG("Call getPositionIK()..."); 00143 00144 // set up the OpenRave IK request 00145 orrosplanning::IK srv; 00146 srv.request.manip_name = "arm"; 00147 srv.request.joint_state.header.frame_id = root_name_; 00148 srv.request.joint_state.position = ik_seed_state; 00149 srv.request.pose_stamped.pose = ik_pose; 00150 srv.request.pose_stamped.header.frame_id = root_name_; 00151 srv.request.pose_stamped.header.stamp = ros::Time::now(); 00152 srv.request.iktype = "TranslationDirection5D"; 00153 srv.request.filteroptions = 0; 00154 00155 ik_service_.call(srv); 00156 00157 if (srv.response.error_code.val == srv.response.error_code.SUCCESS) 00158 { 00159 if (srv.response.solutions.points.size() >= 1) 00160 { 00161 ROS_DEBUG("OpenRave IK found %d solutions,", srv.response.solutions.points.size()); 00162 ROS_DEBUG("in cases of several solutions we discard all despite the first one"); 00163 } 00164 00165 solution.resize(dimension_); 00166 solution = srv.response.solutions.points[0].positions; 00167 error_code = kinematics::SUCCESS; 00168 return true; 00169 } 00170 else 00171 { 00172 ROS_DEBUG("An IK solution could not be found"); 00173 error_code = kinematics::NO_IK_SOLUTION; 00174 return false; 00175 } 00176 } 00177 00178 bool KatanaKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose, 00179 const std::vector<double> &ik_seed_state, const double &timeout, 00180 std::vector<double> &solution, int &error_code) 00181 { 00182 if (!active_) 00183 { 00184 ROS_ERROR("kinematics not active"); 00185 error_code = -8; //kinematics::INACTIVE; 00186 return false; 00187 } 00188 00189 ROS_DEBUG("Call searchPositionIK() without Callback Functions..."); 00190 00191 // set up the OpenRave IK request 00192 orrosplanning::IK srv; 00193 srv.request.manip_name = "arm"; 00194 srv.request.joint_state.header.frame_id = root_name_; 00195 srv.request.joint_state.position = ik_seed_state; 00196 srv.request.pose_stamped.pose = ik_pose; 00197 srv.request.pose_stamped.header.frame_id = root_name_; 00198 srv.request.pose_stamped.header.stamp = ros::Time::now(); 00199 srv.request.iktype = "TranslationDirection5D"; 00200 srv.request.filteroptions = 0; 00201 00202 ik_service_.call(srv); 00203 00204 if (srv.response.error_code.val == srv.response.error_code.SUCCESS) 00205 { 00206 if (srv.response.solutions.points.size() >= 1) 00207 { 00208 ROS_DEBUG("OpenRave IK found %d solutions,", srv.response.solutions.points.size()); 00209 ROS_DEBUG("in cases of several solutions we discard all despite the first one"); 00210 } 00211 00212 solution.resize(dimension_); 00213 solution = srv.response.solutions.points[0].positions; 00214 error_code = kinematics::SUCCESS; 00215 00216 return true; 00217 } 00218 else 00219 { 00220 ROS_DEBUG("An IK solution could not be found"); 00221 error_code = kinematics::NO_IK_SOLUTION; 00222 return false; 00223 } 00224 } 00225 00226 void KatanaKinematicsPlugin::desiredPoseCallback(const std::vector<double>& ik_seed_state, 00227 const geometry_msgs::Pose& ik_pose, 00228 arm_navigation_msgs::ArmNavigationErrorCodes& error_code) 00229 { 00230 00231 int int_error_code; 00232 00233 desiredPoseCallback_(ik_pose, ik_seed_state, int_error_code); 00234 00235 if (int_error_code) 00236 error_code.val = arm_navigation_msgs::ArmNavigationErrorCodes::SUCCESS; 00237 else 00238 error_code.val = arm_navigation_msgs::ArmNavigationErrorCodes::NO_IK_SOLUTION; 00239 } 00240 00241 void KatanaKinematicsPlugin::jointSolutionCallback(const std::vector<double>& solution, 00242 const geometry_msgs::Pose& ik_pose, 00243 arm_navigation_msgs::ArmNavigationErrorCodes& error_code) 00244 { 00245 int int_error_code; 00246 00247 solutionCallback_(ik_pose, solution, int_error_code); 00248 00249 if (int_error_code > 0) 00250 error_code.val = arm_navigation_msgs::ArmNavigationErrorCodes::SUCCESS; 00251 else 00252 error_code.val = arm_navigation_msgs::ArmNavigationErrorCodes::NO_IK_SOLUTION; 00253 } 00254 00255 bool KatanaKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose, 00256 const std::vector<double> &ik_seed_state, const double &timeout, 00257 std::vector<double> &solution, 00258 const boost::function<void(const geometry_msgs::Pose &ik_pose, 00259 const std::vector<double> &ik_solution, 00260 int &error_code)> &desired_pose_callback, 00261 const boost::function<void(const geometry_msgs::Pose &ik_pose, 00262 const std::vector<double> &ik_solution, 00263 int &error_code)> &solution_callback, 00264 int &error_code_int) 00265 { 00266 if (!active_) 00267 { 00268 ROS_ERROR("kinematics not active"); 00269 error_code_int = -8; // kinematics::INACTIVE; 00270 return false; 00271 } 00272 00273 ROS_DEBUG("Call searchPositionIK() with Callback Functions..."); 00274 00275 desiredPoseCallback_ = desired_pose_callback; 00276 solutionCallback_ = solution_callback; 00277 00278 arm_navigation_msgs::ArmNavigationErrorCodes error_code; 00279 00280 // perform IK and check for callback suitability 00281 00282 if (!desired_pose_callback.empty()) 00283 desiredPoseCallback(ik_seed_state, ik_pose, error_code); 00284 00285 if (error_code.val != error_code.SUCCESS) 00286 { 00287 ROS_DEBUG("An IK solution could not be found, because the constraints in desired_pose_callback are not matched"); 00288 error_code_int = kinematics::NO_IK_SOLUTION; 00289 return false; 00290 } 00291 00292 std::vector<double> solution_; 00293 00294 // set up the OpenRave IK request 00295 orrosplanning::IK srv; 00296 srv.request.manip_name = "arm"; 00297 srv.request.joint_state.header.frame_id = root_name_; 00298 srv.request.joint_state.position = ik_seed_state; 00299 srv.request.pose_stamped.header.frame_id = root_name_; 00300 srv.request.pose_stamped.header.stamp = ros::Time::now(); 00301 srv.request.iktype = "TranslationDirection5D"; 00302 srv.request.filteroptions = 0; 00303 00304 srv.request.pose_stamped.pose = ik_pose; 00305 00306 ik_service_.call(srv); 00307 00308 ROS_DEBUG("OpenRave Result %d", srv.response.error_code.val); 00309 00310 if (srv.response.error_code.val == srv.response.error_code.SUCCESS) 00311 { 00312 if (srv.response.solutions.points.size() >= 1) 00313 { 00314 ROS_DEBUG("OpenRave IK found %d solutions", srv.response.solutions.points.size()); 00315 } 00316 solution_.resize(dimension_); 00317 solution_ = srv.response.solutions.points[0].positions; 00318 } 00319 00320 bool callback_check = true; 00321 00322 if (solution_callback.empty()) 00323 callback_check = false; 00324 00325 if (srv.response.error_code.val == srv.response.error_code.SUCCESS) 00326 { 00327 if (callback_check) 00328 { 00329 jointSolutionCallback(solution_, ik_pose, error_code); 00330 00331 if (error_code.val == error_code.SUCCESS) 00332 { 00333 solution.resize(dimension_); 00334 solution = solution_; 00335 error_code_int = kinematics::SUCCESS; 00336 ROS_DEBUG("Plugin sPIK w CB: found ik solution & solution_callback ok"); 00337 return true; 00338 } 00339 else 00340 { 00341 ROS_DEBUG("Plugin sPIK w CB: found IK solution but solution call back fails"); 00342 error_code_int = kinematics::NO_IK_SOLUTION; 00343 return false; 00344 } 00345 00346 } 00347 else 00348 { 00349 error_code.val = error_code.SUCCESS; 00350 solution.resize(dimension_); 00351 solution = solution_; 00352 error_code_int = kinematics::SUCCESS; 00353 ROS_DEBUG("Plugin sPIK w CB: found ik solution & solution call back not necessary"); 00354 return true; 00355 } 00356 } 00357 else 00358 { 00359 ROS_DEBUG("Plugin sPIK w CB: An IK solution could not be found"); 00360 error_code_int = kinematics::NO_IK_SOLUTION; 00361 return false; 00362 } 00363 00364 return false; 00365 } 00366 00367 bool KatanaKinematicsPlugin::getPositionFK(const std::vector<std::string> &link_names, 00368 const std::vector<double> &joint_angles, 00369 std::vector<geometry_msgs::Pose> &poses) 00370 { 00371 if (!active_) 00372 { 00373 ROS_ERROR("kinematics not active"); 00374 return false; 00375 } 00376 00377 ROS_DEBUG("Plugin: Call getPositionFK()..."); 00378 00379 kinematics_msgs::GetPositionFK srv; 00380 00381 srv.request.header.frame_id = root_name_; 00382 srv.request.fk_link_names = link_names; 00383 srv.request.robot_state.joint_state.name = fk_solver_info_.joint_names; 00384 srv.request.robot_state.joint_state.position = joint_angles; 00385 00386 fk_service_.call(srv); 00387 00388 poses.resize(link_names.size()); 00389 00390 if (srv.response.error_code.val == srv.response.error_code.NO_FK_SOLUTION) 00391 { 00392 ROS_DEBUG("Plugin: Could not find a FK"); 00393 return false; 00394 } 00395 00396 if (srv.response.error_code.val == srv.response.error_code.SUCCESS) 00397 { 00398 ROS_DEBUG("Successfully computed FK..."); 00399 00400 for (size_t i = 0; i < poses.size(); i++) 00401 { 00402 poses[i] = srv.response.pose_stamped[i].pose; 00403 ROS_DEBUG("PLUGIN Joint: %s Pose: %f %f %f // %f %f %f %f", link_names[i].c_str(), 00404 poses[i].position.x, 00405 poses[i].position.y, 00406 poses[i].position.z, 00407 poses[i].orientation.x, 00408 poses[i].orientation.y, 00409 poses[i].orientation.z, 00410 poses[i].orientation.w); 00411 } 00412 00413 return true; 00414 } 00415 else 00416 { 00417 00418 ROS_DEBUG("Plugin: Could not compute FK"); 00419 00420 return false; 00421 } 00422 } 00423 00424 std::string KatanaKinematicsPlugin::getBaseFrame() 00425 { 00426 if (!active_) 00427 { 00428 ROS_ERROR("kinematics not active"); 00429 return std::string(""); 00430 } 00431 return root_name_; 00432 } 00433 00434 std::string KatanaKinematicsPlugin::getToolFrame() 00435 { 00436 if (!active_ || ik_solver_info_.link_names.empty()) 00437 { 00438 ROS_ERROR("kinematics not active"); 00439 return std::string(""); 00440 } 00441 00442 return ik_solver_info_.link_names[0]; 00443 } 00444 00445 std::vector<std::string> KatanaKinematicsPlugin::getJointNames() 00446 { 00447 if (!active_) 00448 { 00449 std::vector<std::string> empty; 00450 ROS_ERROR("kinematics not active"); 00451 return empty; 00452 } 00453 return ik_solver_info_.joint_names; 00454 } 00455 00456 std::vector<std::string> KatanaKinematicsPlugin::getLinkNames() 00457 { 00458 if (!active_) 00459 { 00460 std::vector<std::string> empty; 00461 ROS_ERROR("kinematics not active"); 00462 return empty; 00463 } 00464 00465 return fk_solver_info_.link_names; 00466 } 00467 00468 } 00469 // namespace