$search
00001 /* 00002 * Software License Agreement (Modified BSD License) 00003 * 00004 * Copyright (c) 2012, PAL Robotics, S.L. 00005 * Copyright (c) 2008, Willow Garage, Inc. 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of PAL Robotics, S.L. nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 */ 00035 00040 #include <reem_kinematics_constraint_aware/reem_arm_kinematics_plugin.h> 00041 #include <pluginlib/class_list_macros.h> 00042 00043 using namespace KDL; 00044 using namespace tf; 00045 using namespace std; 00046 using namespace ros; 00047 00048 const double BOUNDS_EPSILON = .00001; 00049 00050 //register ReemKinematics as a KinematicsBase implementation 00051 PLUGINLIB_DECLARE_CLASS(reem_kinematics_constraint_aware,ReemKinematicsPlugin, reem_kinematics_constraint_aware::ReemKinematicsPlugin, kinematics::KinematicsBase) 00052 00053 namespace reem_kinematics_constraint_aware { 00054 00055 ReemKinematicsPlugin::ReemKinematicsPlugin():active_(false) 00056 { 00057 srand ( time(NULL) ); 00058 } 00059 00060 bool ReemKinematicsPlugin::isActive() 00061 { 00062 if(active_) 00063 return true; 00064 return false; 00065 } 00066 00067 double ReemKinematicsPlugin::genRandomNumber(const double &min, const double &max) 00068 { 00069 int rand_num = rand()%100+1; 00070 double result = min + (double)((max-min)*rand_num)/101.0; 00071 return result; 00072 } 00073 00074 KDL::JntArray ReemKinematicsPlugin::getRandomConfiguration() 00075 { 00076 KDL::JntArray jnt_array; 00077 jnt_array.resize(dimension_); 00078 for(unsigned int i=0; i < dimension_; ++i) 00079 jnt_array(i) = genRandomNumber(joint_min_(i),joint_max_(i)); 00080 return jnt_array; 00081 } 00082 00083 bool ReemKinematicsPlugin::initialize(std::string name) 00084 { 00085 // Get URDF XML 00086 std::string urdf_xml, full_urdf_xml; 00087 ros::NodeHandle node_handle; 00088 ros::NodeHandle private_handle("~"+name); 00089 ROS_INFO_STREAM("Private handle registered under " << private_handle.getNamespace()); 00090 node_handle.param("urdf_xml",urdf_xml,std::string("robot_description")); 00091 node_handle.searchParam(urdf_xml,full_urdf_xml); 00092 ROS_DEBUG("Reading xml file from parameter server"); 00093 std::string result; 00094 if (!node_handle.getParam(full_urdf_xml, result)) { 00095 ROS_FATAL("Could not load the xml from parameter server: %s", urdf_xml.c_str()); 00096 return false; 00097 } 00098 00099 // Get Root and Tip From Parameter Service 00100 if (!private_handle.getParam("root_name", root_name_)) { 00101 ROS_FATAL("GenericIK: No root name found on parameter server"); 00102 return false; 00103 } 00104 if (!private_handle.getParam("tip_name", tip_name_)) { 00105 ROS_FATAL("GenericIK: No tip name found on parameter server"); 00106 return false; 00107 } 00108 // Load and Read Models 00109 if (!loadModel(result)) { 00110 ROS_FATAL("Could not load models!"); 00111 return false; 00112 } 00113 00114 // Populate map from joint names to KDL tree indices 00115 std::map<std::string, int> joint_name_to_idx; 00116 for (size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i) 00117 { 00118 const KDL::Joint& joint = kdl_chain_.getSegment(i).getJoint(); 00119 if (joint.getType() != KDL::Joint::None) 00120 { 00121 joint_name_to_idx[joint.getName()] = i; 00122 } 00123 } 00124 00125 // Space diensions 00126 const int q_dim = kdl_chain_.getNrOfJoints(); 00127 const int x_dim = 6; 00128 00129 // Get Solver Parameters 00130 int max_iterations; 00131 double epsilon; 00132 double max_delta_x; 00133 double max_delta_q; 00134 double velik_gain; 00135 00136 private_handle.param("max_solver_iterations", max_iterations, 500); 00137 private_handle.param("max_search_iterations", max_search_iterations_, 3); 00138 private_handle.param("epsilon", epsilon, 1e-5); 00139 private_handle.param("max_delta_x", max_delta_x, 0.006); 00140 private_handle.param("max_delta_q", max_delta_q, 0.03); 00141 private_handle.param("velik_gain", velik_gain, 1.0); 00142 00143 // Joint space weights diagonal matrix inverse and default posture 00144 Eigen::VectorXd Wqinv = Eigen::VectorXd::Ones(q_dim); 00145 default_posture_.resize(q_dim); 00146 for (size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i) 00147 { 00148 const KDL::Joint& joint = kdl_chain_.getSegment(i).getJoint(); 00149 if (joint.getType() != KDL::Joint::None) 00150 { 00151 private_handle.param("joint_weights/" + joint.getName(), Wqinv(joint_name_to_idx[joint.getName()]), 1.0); 00152 private_handle.param("default_posture/" + joint.getName(), default_posture_[joint_name_to_idx[joint.getName()]], 0.0); 00153 } 00154 } 00155 00156 // Task space weights diagonal matrix 00157 Eigen::VectorXd Wxinv = Eigen::VectorXd::Ones(x_dim); 00158 private_handle.param("task_weights/position/x", Wxinv(0), 1.0); 00159 private_handle.param("task_weights/position/y", Wxinv(1), 1.0); 00160 private_handle.param("task_weights/position/z", Wxinv(2), 1.0); 00161 private_handle.param("task_weights/orientation/x", Wxinv(3), 1.0); 00162 private_handle.param("task_weights/orientation/y", Wxinv(4), 1.0); 00163 private_handle.param("task_weights/orientation/z", Wxinv(5), 1.0); 00164 00165 // Build Solvers 00166 fk_solver_.reset(new KDL::ChainFkSolverPos_recursive(kdl_chain_)); 00167 ik_solver_.reset(new IkSolver(kdl_chain_)); 00168 ik_solver_->setJointPositionLimits(joint_min_.data, joint_max_.data); 00169 ik_solver_->setEpsilon(epsilon); 00170 ik_solver_->setMaxIterations(max_iterations); 00171 ik_solver_->setMaxDeltaPosTask(max_delta_x); 00172 ik_solver_->setMaxDeltaPosJoint(max_delta_q); 00173 ik_solver_->setVelocityIkGain(velik_gain); 00174 ik_solver_->setJointSpaceWeights(Wqinv); 00175 ik_solver_->setTaskSpaceWeights(Wxinv); 00176 active_ = true; 00177 return true; 00178 } 00179 00180 bool ReemKinematicsPlugin::loadModel(const std::string xml) 00181 { 00182 urdf::Model robot_model; 00183 KDL::Tree tree; 00184 00185 if (!robot_model.initString(xml)) { 00186 ROS_FATAL("Could not initialize robot model"); 00187 return -1; 00188 } 00189 if (!kdl_parser::treeFromString(xml, tree)) { 00190 ROS_ERROR("Could not initialize tree object"); 00191 return false; 00192 } 00193 if (!tree.getChain(root_name_, tip_name_, kdl_chain_)) { 00194 ROS_ERROR("Could not initialize chain object"); 00195 return false; 00196 } 00197 if (!readJoints(robot_model)) { 00198 ROS_FATAL("Could not read information about the joints"); 00199 return false; 00200 } 00201 return true; 00202 } 00203 00204 bool ReemKinematicsPlugin::readJoints(urdf::Model &robot_model) 00205 { 00206 dimension_ = 0; 00207 // get joint maxs and mins 00208 boost::shared_ptr<const urdf::Link> link = robot_model.getLink(tip_name_); 00209 boost::shared_ptr<const urdf::Joint> joint; 00210 while (link && link->name != root_name_) { 00211 joint = robot_model.getJoint(link->parent_joint->name); 00212 if (!joint) { 00213 ROS_ERROR("Could not find joint: %s",link->parent_joint->name.c_str()); 00214 return false; 00215 } 00216 if (joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED) { 00217 ROS_INFO( "adding joint: [%s]", joint->name.c_str() ); 00218 dimension_++; 00219 } 00220 link = robot_model.getLink(link->getParent()->name); 00221 } 00222 joint_min_.resize(dimension_); 00223 joint_max_.resize(dimension_); 00224 chain_info_.joint_names.resize(dimension_); 00225 chain_info_.limits.resize(dimension_); 00226 link = robot_model.getLink(tip_name_); 00227 if(link) 00228 chain_info_.link_names.push_back(tip_name_); 00229 00230 unsigned int i = 0; 00231 while (link && i < dimension_) { 00232 joint = robot_model.getJoint(link->parent_joint->name); 00233 if (joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED) { 00234 ROS_INFO( "getting bounds for joint: [%s]", joint->name.c_str() ); 00235 00236 float lower, upper; 00237 int hasLimits; 00238 if ( joint->type != urdf::Joint::CONTINUOUS ) { 00239 if(joint->safety) { 00240 lower = joint->safety->soft_lower_limit+BOUNDS_EPSILON; 00241 upper = joint->safety->soft_upper_limit-BOUNDS_EPSILON; 00242 } else { 00243 lower = joint->limits->lower+BOUNDS_EPSILON; 00244 upper = joint->limits->upper-BOUNDS_EPSILON; 00245 } 00246 hasLimits = 1; 00247 } else { 00248 lower = -M_PI; 00249 upper = M_PI; 00250 hasLimits = 0; 00251 } 00252 int index = dimension_ - i -1; 00253 00254 joint_min_.data[index] = lower; 00255 joint_max_.data[index] = upper; 00256 chain_info_.joint_names[index] = joint->name; 00257 chain_info_.limits[index].joint_name = joint->name; 00258 chain_info_.limits[index].has_position_limits = hasLimits; 00259 chain_info_.limits[index].min_position = lower; 00260 chain_info_.limits[index].max_position = upper; 00261 ++i; 00262 } 00263 link = robot_model.getLink(link->getParent()->name); 00264 } 00265 return true; 00266 } 00267 00268 int ReemKinematicsPlugin::getJointIndex(const std::string &name) 00269 { 00270 for (unsigned int i=0; i < chain_info_.joint_names.size(); ++i) { 00271 if (chain_info_.joint_names[i] == name) 00272 return i; 00273 } 00274 return -1; 00275 } 00276 00277 int ReemKinematicsPlugin::getKDLSegmentIndex(const std::string &name) 00278 { 00279 int i=0; 00280 while (i < (int)kdl_chain_.getNrOfSegments()) { 00281 if (kdl_chain_.getSegment(i).getName() == name) { 00282 return i+1; 00283 } 00284 ++i; 00285 } 00286 return -1; 00287 } 00288 00289 bool ReemKinematicsPlugin::getPositionIK(const geometry_msgs::Pose &ik_pose, 00290 const std::vector<double> &ik_seed_state, 00291 const std::vector<double> &posture, 00292 std::vector<double> &solution, 00293 int &error_code) 00294 { 00295 ros::WallTime n1 = ros::WallTime::now(); 00296 if(!active_) 00297 { 00298 ROS_ERROR("kinematics not active"); 00299 return false; 00300 } 00301 00302 ROS_DEBUG_STREAM("getPositionIK1:Position request pose is " << 00303 ik_pose.position.x << " " << 00304 ik_pose.position.y << " " << 00305 ik_pose.position.z << " " << 00306 ik_pose.orientation.x << " " << 00307 ik_pose.orientation.y << " " << 00308 ik_pose.orientation.z << " " << 00309 ik_pose.orientation.w); 00310 00311 KDL::Frame pose_desired; 00312 tf::PoseMsgToKDL(ik_pose, pose_desired); 00313 //Do the inverse kinematics 00314 KDL::JntArray jnt_pos_in(dimension_); 00315 KDL::JntArray jnt_pos_out(dimension_); 00316 KDL::JntArray jnt_posture(dimension_); 00317 for(unsigned int i=0; i < dimension_; ++i) 00318 { 00319 jnt_pos_in(i) = ik_seed_state[i]; 00320 jnt_posture(i) = posture[i]; 00321 } 00322 ik_solver_->setPosture(jnt_posture); 00323 bool ik_valid = ik_solver_->solve(jnt_pos_in, pose_desired, jnt_pos_out); 00324 ROS_DEBUG_STREAM("IK success " << ik_valid << " time " << (ros::WallTime::now()-n1).toSec()); 00325 solution.resize(dimension_); 00326 // NOTE: In the original implementation, the solution is not reported if IK failed. We do populate the best estimate 00327 for(unsigned int i=0; i < dimension_; ++i) 00328 { 00329 solution[i] = jnt_pos_out(i); 00330 } 00331 if(ik_valid) 00332 { 00333 error_code = kinematics::SUCCESS; 00334 return true; 00335 } 00336 else 00337 { 00338 ROS_DEBUG("An IK solution could not be found"); 00339 error_code = kinematics::NO_IK_SOLUTION; 00340 return false; 00341 } 00342 } 00343 00344 bool ReemKinematicsPlugin::getPositionIK(const geometry_msgs::Pose &ik_pose, 00345 const std::vector<double> &ik_seed_state, 00346 std::vector<double> &solution, 00347 int &error_code) 00348 { 00349 return getPositionIK(ik_pose, 00350 ik_seed_state, 00351 default_posture_, 00352 solution, 00353 error_code); 00354 } 00355 00356 bool ReemKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose, 00357 const std::vector<double> &ik_seed_state, 00358 const double &timeout, 00359 std::vector<double> &solution, 00360 int &error_code) 00361 { 00362 ros::WallTime n1 = ros::WallTime::now(); 00363 if(!active_) 00364 { 00365 ROS_ERROR("kinematics not active"); 00366 error_code = kinematics::INACTIVE; 00367 return false; 00368 } 00369 KDL::Frame pose_desired; 00370 tf::PoseMsgToKDL(ik_pose, pose_desired); 00371 00372 ROS_DEBUG_STREAM("searchPositionIK1:Position request pose is " << 00373 ik_pose.position.x << " " << 00374 ik_pose.position.y << " " << 00375 ik_pose.position.z << " " << 00376 ik_pose.orientation.x << " " << 00377 ik_pose.orientation.y << " " << 00378 ik_pose.orientation.z << " " << 00379 ik_pose.orientation.w); 00380 00381 //Do the IK 00382 KDL::JntArray jnt_pos_in; 00383 KDL::JntArray jnt_pos_out; 00384 jnt_pos_in.resize(dimension_); 00385 KDL::JntArray posture(dimension_); 00386 for(unsigned int i=0; i < dimension_; ++i) 00387 { 00388 jnt_pos_in(i) = ik_seed_state[i]; 00389 posture(i) = default_posture_[i]; 00390 } 00391 for(int i=0; i < max_search_iterations_; ++i) 00392 { 00393 for(unsigned int j=0; j < dimension_; ++j) 00394 { 00395 ROS_DEBUG_STREAM("seed state " << j << " " << jnt_pos_in(j)); 00396 } 00397 ik_solver_->setPosture(posture); 00398 bool ik_valid = ik_solver_->solve(jnt_pos_in, pose_desired, jnt_pos_out); 00399 ROS_DEBUG_STREAM("IK success " << ik_valid << " time " << (ros::WallTime::now()-n1).toSec()); 00400 if(ik_valid) { 00401 solution.resize(dimension_); 00402 for(unsigned int j=0; j < dimension_; ++j) { 00403 solution[j] = jnt_pos_out(j); 00404 } 00405 error_code = kinematics::SUCCESS; 00406 ROS_DEBUG_STREAM("Solved after " << i+1 << " iterations"); 00407 return true; 00408 } 00409 jnt_pos_in = getRandomConfiguration(); 00410 } 00411 ROS_DEBUG("An IK solution could not be found"); 00412 error_code = kinematics::NO_IK_SOLUTION; 00413 return false; 00414 } 00415 00416 bool ReemKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose, 00417 const std::vector<double> &ik_seed_state, 00418 const double &timeout, 00419 std::vector<double> &solution, 00420 const boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> &desired_pose_callback, 00421 const boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> &solution_callback, 00422 int &error_code) 00423 { 00424 if(!active_) 00425 { 00426 ROS_ERROR("kinematics not active"); 00427 error_code = kinematics::INACTIVE; 00428 return false; 00429 } 00430 KDL::Frame pose_desired; 00431 tf::PoseMsgToKDL(ik_pose, pose_desired); 00432 00433 ROS_DEBUG_STREAM("searchPositionIK2: Position request pose is " << 00434 ik_pose.position.x << " " << 00435 ik_pose.position.y << " " << 00436 ik_pose.position.z << " " << 00437 ik_pose.orientation.x << " " << 00438 ik_pose.orientation.y << " " << 00439 ik_pose.orientation.z << " " << 00440 ik_pose.orientation.w); 00441 00442 //Do the IK 00443 KDL::JntArray jnt_pos_in; 00444 KDL::JntArray jnt_pos_out; 00445 jnt_pos_in.resize(dimension_); 00446 KDL::JntArray posture(dimension_); 00447 for(unsigned int i=0; i < dimension_; ++i) 00448 { 00449 jnt_pos_in(i) = ik_seed_state[i]; 00450 posture(i) = default_posture_[i]; 00451 } 00452 00453 if(!desired_pose_callback.empty()) 00454 desired_pose_callback(ik_pose,ik_seed_state,error_code); 00455 00456 if(error_code < 0) 00457 { 00458 ROS_DEBUG("Could not find inverse kinematics for desired end-effector pose since the pose may be in collision"); 00459 return false; 00460 } 00461 for(int i=0; i < max_search_iterations_; ++i) 00462 { 00463 ik_solver_->setPosture(posture); 00464 bool ik_valid = ik_solver_->solve(jnt_pos_in, pose_desired, jnt_pos_out); 00465 jnt_pos_in = getRandomConfiguration(); 00466 if(!ik_valid) 00467 continue; 00468 std::vector<double> solution_local; 00469 solution_local.resize(dimension_); 00470 for(unsigned int j=0; j < dimension_; ++j) 00471 solution_local[j] = jnt_pos_out(j); 00472 solution_callback(ik_pose,solution_local,error_code); 00473 if(error_code == kinematics::SUCCESS) 00474 { 00475 solution = solution_local; 00476 ROS_DEBUG_STREAM("Solved after " << i+1 << " iterations"); 00477 return true; 00478 } 00479 } 00480 ROS_DEBUG("An IK that satisifes the constraints and is collision free could not be found"); 00481 error_code = kinematics::NO_IK_SOLUTION; 00482 return false; 00483 } 00484 00485 bool ReemKinematicsPlugin::getPositionFK(const std::vector<std::string> &link_names, 00486 const std::vector<double> &joint_angles, 00487 std::vector<geometry_msgs::Pose> &poses) 00488 { 00489 if(!active_) 00490 { 00491 ROS_ERROR("kinematics not active"); 00492 return false; 00493 } 00494 00495 KDL::Frame p_out; 00496 KDL::JntArray jnt_pos_in; 00497 geometry_msgs::PoseStamped pose; 00498 tf::Stamped<tf::Pose> tf_pose; 00499 00500 jnt_pos_in.resize(dimension_); 00501 for(unsigned int i=0; i < dimension_; ++i) 00502 { 00503 jnt_pos_in(i) = joint_angles[i]; 00504 } 00505 00506 poses.resize(link_names.size()); 00507 00508 bool valid = true; 00509 for(unsigned int i=0; i < poses.size(); ++i) 00510 { 00511 if(fk_solver_->JntToCart(jnt_pos_in,p_out,getKDLSegmentIndex(link_names[i])) >=0) 00512 { 00513 tf::PoseKDLToMsg(p_out,poses[i]); 00514 } 00515 else 00516 { 00517 ROS_ERROR("Could not compute FK for %s",link_names[i].c_str()); 00518 valid = false; 00519 } 00520 } 00521 return valid; 00522 } 00523 00524 std::string ReemKinematicsPlugin::getBaseFrame() 00525 { 00526 if(!active_) 00527 { 00528 ROS_ERROR("kinematics not active"); 00529 return std::string(""); 00530 } 00531 return root_name_; 00532 } 00533 00534 std::string ReemKinematicsPlugin::getToolFrame() 00535 { 00536 if(!active_ || chain_info_.link_names.empty()) 00537 { 00538 ROS_ERROR("kinematics not active"); 00539 return std::string(""); 00540 } 00541 return chain_info_.link_names[0]; 00542 } 00543 00544 std::vector<std::string> ReemKinematicsPlugin::getJointNames() 00545 { 00546 if(!active_) 00547 { 00548 std::vector<std::string> empty; 00549 ROS_ERROR("kinematics not active"); 00550 return empty; 00551 } 00552 return chain_info_.joint_names; 00553 } 00554 00555 std::vector<std::string> ReemKinematicsPlugin::getLinkNames() 00556 { 00557 if(!active_) 00558 { 00559 std::vector<std::string> empty; 00560 ROS_ERROR("kinematics not active"); 00561 return empty; 00562 } 00563 return chain_info_.link_names; 00564 } 00565 00566 } // namespace