00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #include <trac_ik/trac_ik.hpp>
00033 #include <boost/date_time.hpp>
00034 #include <boost/make_shared.hpp>
00035 #include <Eigen/Geometry>
00036 #include <ros/ros.h>
00037 #include <limits>
00038 #include <kdl_parser/kdl_parser.hpp>
00039 #include <urdf/model.h>
00040
00041 namespace TRAC_IK {
00042
00043 TRAC_IK::TRAC_IK(const std::string& base_link, const std::string& tip_link, const std::string& URDF_param, double _maxtime, double _eps, SolveType _type ) :
00044 initialized(false),
00045 eps(_eps),
00046 maxtime(_maxtime),
00047 solvetype(_type),
00048 work(io_service)
00049 {
00050
00051 ros::NodeHandle node_handle("~");
00052
00053 urdf::Model robot_model;
00054 std::string xml_string;
00055
00056 std::string urdf_xml,full_urdf_xml;
00057 node_handle.param("urdf_xml",urdf_xml,URDF_param);
00058 node_handle.searchParam(urdf_xml,full_urdf_xml);
00059
00060 ROS_DEBUG_NAMED("trac_ik","Reading xml file from parameter server");
00061 if (!node_handle.getParam(full_urdf_xml, xml_string))
00062 {
00063 ROS_FATAL_NAMED("trac_ik","Could not load the xml from parameter server: %s", urdf_xml.c_str());
00064 return;
00065 }
00066
00067 node_handle.param(full_urdf_xml,xml_string,std::string());
00068 robot_model.initString(xml_string);
00069
00070 ROS_DEBUG_STREAM_NAMED("trac_ik","Reading joints and links from URDF");
00071
00072 KDL::Tree tree;
00073
00074 if (!kdl_parser::treeFromUrdfModel(robot_model, tree))
00075 ROS_FATAL("Failed to extract kdl tree from xml robot description");
00076
00077 if(!tree.getChain(base_link, tip_link, chain))
00078 ROS_FATAL("Couldn't find chain %s to %s",base_link.c_str(),tip_link.c_str());
00079
00080 std::vector<KDL::Segment> chain_segs = chain.segments;
00081
00082 boost::shared_ptr<const urdf::Joint> joint;
00083
00084 std::vector<double> l_bounds, u_bounds;
00085
00086 lb.resize(chain.getNrOfJoints());
00087 ub.resize(chain.getNrOfJoints());
00088
00089 uint joint_num=0;
00090 for(unsigned int i = 0; i < chain_segs.size(); ++i) {
00091 joint = robot_model.getJoint(chain_segs[i].getJoint().getName());
00092 if (joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED) {
00093 joint_num++;
00094 float lower, upper;
00095 int hasLimits;
00096 if ( joint->type != urdf::Joint::CONTINUOUS ) {
00097 if(joint->safety) {
00098 lower = std::max(joint->limits->lower, joint->safety->soft_lower_limit);
00099 upper = std::min(joint->limits->upper, joint->safety->soft_upper_limit);
00100 } else {
00101 lower = joint->limits->lower;
00102 upper = joint->limits->upper;
00103 }
00104 hasLimits = 1;
00105 }
00106 else {
00107 hasLimits = 0;
00108 }
00109 if(hasLimits) {
00110 lb(joint_num-1)=lower;
00111 ub(joint_num-1)=upper;
00112 }
00113 else {
00114 lb(joint_num-1)=std::numeric_limits<float>::lowest();
00115 ub(joint_num-1)=std::numeric_limits<float>::max();
00116 }
00117 ROS_INFO_STREAM("IK Using joint "<<joint->name<<" "<<lb(joint_num-1)<<" "<<ub(joint_num-1));
00118 }
00119 }
00120
00121 initialize();
00122 }
00123
00124
00125 TRAC_IK::TRAC_IK(const KDL::Chain& _chain, const KDL::JntArray& _q_min, const KDL::JntArray& _q_max, double _maxtime, double _eps, SolveType _type):
00126 initialized(false),
00127 chain(_chain),
00128 lb(_q_min),
00129 ub(_q_max),
00130 eps(_eps),
00131 maxtime(_maxtime),
00132 solvetype(_type),
00133 work(io_service)
00134 {
00135
00136 initialize();
00137 }
00138
00139 void TRAC_IK::initialize() {
00140
00141 assert(chain.getNrOfJoints()==lb.data.size());
00142 assert(chain.getNrOfJoints()==ub.data.size());
00143
00144 jacsolver.reset(new KDL::ChainJntToJacSolver(chain));
00145 nl_solver.reset(new NLOPT_IK::NLOPT_IK(chain,lb,ub,maxtime,eps,NLOPT_IK::SumSq));
00146 iksolver.reset(new KDL::ChainIkSolverPos_TL(chain,lb,ub,maxtime,eps,true,true));
00147
00148 for (uint i=0; i<chain.segments.size(); i++) {
00149 std::string type = chain.segments[i].getJoint().getTypeName();
00150 if (type.find("Rot")!=std::string::npos) {
00151 if (ub(types.size())>=std::numeric_limits<float>::max() &&
00152 lb(types.size())<=std::numeric_limits<float>::lowest())
00153 types.push_back(KDL::BasicJointType::Continuous);
00154 else
00155 types.push_back(KDL::BasicJointType::RotJoint);
00156 }
00157 else if (type.find("Trans")!=std::string::npos)
00158 types.push_back(KDL::BasicJointType::TransJoint);
00159 }
00160
00161 assert(types.size()==lb.data.size());
00162
00163
00164 threads.create_thread(boost::bind(&boost::asio::io_service::run,
00165 &io_service));
00166 threads.create_thread(boost::bind(&boost::asio::io_service::run,
00167 &io_service));
00168
00169 initialized = true;
00170 }
00171
00172 bool TRAC_IK::unique_solution(const KDL::JntArray& sol) {
00173
00174 for (uint i=0; i< solutions.size(); i++)
00175 if (myEqual(sol,solutions[i]))
00176 return false;
00177 return true;
00178
00179 }
00180
00181 inline void normalizeAngle(double& val, const double& min, const double& max)
00182 {
00183 if (val > max) {
00184
00185 double diffangle = fmod(val-max,2*M_PI);
00186
00187 val = max + diffangle - 2*M_PI;
00188 }
00189
00190 if (val < min) {
00191
00192 double diffangle = fmod(min-val,2*M_PI);
00193
00194 val = min - diffangle + 2*M_PI;
00195 }
00196 }
00197
00198 inline void normalizeAngle(double& val, const double& target)
00199 {
00200 if (val > target+M_PI) {
00201
00202 double diffangle = fmod(val-target,2*M_PI);
00203
00204 val = target + diffangle - 2*M_PI;
00205 }
00206
00207 if (val < target-M_PI) {
00208
00209 double diffangle = fmod(target-val,2*M_PI);
00210
00211 val = target - diffangle + 2*M_PI;
00212 }
00213 }
00214
00215
00216 bool TRAC_IK::runKDL(const KDL::JntArray &q_init, const KDL::Frame &p_in)
00217 {
00218 KDL::JntArray q_out;
00219
00220 double fulltime = maxtime;
00221 KDL::JntArray seed = q_init;
00222
00223 boost::posix_time::time_duration timediff;
00224 double time_left;
00225
00226 while (true) {
00227 timediff=boost::posix_time::microsec_clock::local_time()-start_time;
00228 time_left = fulltime - timediff.total_nanoseconds()/1000000000.0;
00229
00230 if (time_left <= 0)
00231 break;
00232
00233 iksolver->setMaxtime(time_left);
00234
00235 int kdlRC = iksolver->CartToJnt(seed,p_in,q_out,bounds);
00236 if (kdlRC >=0) {
00237 switch (solvetype) {
00238 case Manip1:
00239 case Manip2:
00240 normalize_limits(q_init, q_out);
00241 break;
00242 default:
00243 normalize_seed(q_init, q_out);
00244 break;
00245 }
00246 mtx_.lock();
00247 if (unique_solution(q_out)) {
00248 solutions.push_back(q_out);
00249 uint curr_size=solutions.size();
00250 errors.resize(curr_size);
00251 mtx_.unlock();
00252 double err, penalty;
00253 switch (solvetype) {
00254 case Manip1:
00255 penalty = manipPenalty(q_out);
00256 err = penalty*TRAC_IK::ManipValue1(q_out);
00257 break;
00258 case Manip2:
00259 penalty = manipPenalty(q_out);
00260 err = penalty*TRAC_IK::ManipValue2(q_out);
00261 break;
00262 default:
00263 err = TRAC_IK::JointErr(q_init,q_out);
00264 break;
00265 }
00266 mtx_.lock();
00267 errors[curr_size-1] = std::make_pair(err,curr_size-1);
00268 }
00269 mtx_.unlock();
00270 }
00271
00272 if (!solutions.empty() && solvetype == Speed)
00273 break;
00274
00275 for (unsigned int j=0; j<seed.data.size(); j++)
00276 if (types[j]==KDL::BasicJointType::Continuous)
00277 seed(j)=fRand(q_init(j)-2*M_PI, q_init(j)+2*M_PI);
00278 else
00279 seed(j)=fRand(lb(j), ub(j));
00280 }
00281 nl_solver->abort();
00282
00283 iksolver->setMaxtime(fulltime);
00284
00285 return true;
00286 }
00287
00288 bool TRAC_IK::runNLOPT(const KDL::JntArray &q_init, const KDL::Frame &p_in)
00289 {
00290 KDL::JntArray q_out;
00291
00292 double fulltime = maxtime;
00293 KDL::JntArray seed = q_init;
00294
00295 boost::posix_time::time_duration timediff;
00296 double time_left;
00297
00298 while (true) {
00299 timediff=boost::posix_time::microsec_clock::local_time()-start_time;
00300 time_left = fulltime - timediff.total_nanoseconds()/1000000000.0;
00301
00302 if (time_left <= 0)
00303 break;
00304
00305 nl_solver->setMaxtime(time_left);
00306
00307 int nloptRC = nl_solver->CartToJnt(seed,p_in,q_out,bounds);
00308 if (nloptRC >=0) {
00309 switch (solvetype) {
00310 case Manip1:
00311 case Manip2:
00312 normalize_limits(q_init, q_out);
00313 break;
00314 default:
00315 normalize_seed(q_init, q_out);
00316 break;
00317 }
00318 mtx_.lock();
00319 if (unique_solution(q_out)) {
00320 solutions.push_back(q_out);
00321 uint curr_size=solutions.size();
00322 errors.resize(curr_size);
00323 mtx_.unlock();
00324 double err, penalty;
00325 switch (solvetype) {
00326 case Manip1:
00327 penalty = manipPenalty(q_out);
00328 err = penalty*TRAC_IK::ManipValue1(q_out);
00329 break;
00330 case Manip2:
00331 penalty = manipPenalty(q_out);
00332 err = penalty*TRAC_IK::ManipValue2(q_out);
00333 break;
00334 default:
00335 err = TRAC_IK::JointErr(q_init,q_out);
00336 break;
00337 }
00338 mtx_.lock();
00339 errors[curr_size-1] = std::make_pair(err,curr_size-1);
00340 }
00341 mtx_.unlock();
00342 }
00343
00344 if (!solutions.empty() && solvetype == Speed)
00345 break;
00346
00347 for (unsigned int j=0; j<seed.data.size(); j++)
00348 if (types[j]==KDL::BasicJointType::Continuous)
00349 seed(j)=fRand(q_init(j)-2*M_PI, q_init(j)+2*M_PI);
00350 else
00351 seed(j)=fRand(lb(j), ub(j));
00352 }
00353
00354 iksolver->abort();
00355
00356 nl_solver->setMaxtime(fulltime);
00357
00358 return true;
00359 }
00360
00361 void TRAC_IK::normalize_seed(const KDL::JntArray& seed, KDL::JntArray& solution) {
00362
00363
00364
00365 bool improved = false;
00366
00367 for (uint i=0; i<lb.data.size(); i++) {
00368
00369 if (types[i]==KDL::BasicJointType::TransJoint)
00370 continue;
00371
00372 double target = seed(i);
00373 double val = solution(i);
00374
00375 normalizeAngle( val, target );
00376
00377 if (types[i]==KDL::BasicJointType::Continuous) {
00378 solution(i) = val;
00379 continue;
00380 }
00381
00382 normalizeAngle( val, lb(i), ub(i) );
00383
00384 solution(i) = val;
00385 }
00386 }
00387
00388 void TRAC_IK::normalize_limits(const KDL::JntArray& seed, KDL::JntArray& solution) {
00389
00390
00391
00392 bool improved = false;
00393
00394 for (uint i=0; i<lb.data.size(); i++) {
00395
00396 if (types[i] == KDL::BasicJointType::TransJoint)
00397 continue;
00398
00399 double target = seed(i);
00400
00401 if (types[i] == KDL::BasicJointType::RotJoint && types[i]!=KDL::BasicJointType::Continuous)
00402 target = (ub(i)+lb(i))/2.0;
00403
00404 double val = solution(i);
00405
00406 normalizeAngle( val, target );
00407
00408 if (types[i]==KDL::BasicJointType::Continuous) {
00409 solution(i) = val;
00410 continue;
00411 }
00412
00413 normalizeAngle( val, lb(i), ub(i) );
00414
00415 solution(i) = val;
00416 }
00417
00418 }
00419
00420
00421 double TRAC_IK::manipPenalty(const KDL::JntArray& arr) {
00422 double penalty = 1.0;
00423 for (uint i=0; i< arr.data.size(); i++) {
00424 if (types[i] == KDL::BasicJointType::Continuous)
00425 continue;
00426 double range = ub(i)-lb(i);
00427 penalty *= ((arr(i)-lb(i))*(ub(i)-arr(i))/(range*range));
00428 }
00429 return std::max(0.0,1.0 - exp(-1*penalty));
00430 }
00431
00432
00433 double TRAC_IK::ManipValue1(const KDL::JntArray& arr) {
00434 KDL::Jacobian jac(arr.data.size());
00435
00436 jacsolver->JntToJac(arr,jac);
00437
00438 Eigen::JacobiSVD<Eigen::MatrixXd> svdsolver(jac.data);
00439 Eigen::MatrixXd singular_values = svdsolver.singularValues();
00440
00441 double error = 1.0;
00442 for(unsigned int i=0; i < singular_values.rows(); ++i)
00443 error *= singular_values(i,0);
00444 return error;
00445 }
00446
00447 double TRAC_IK::ManipValue2(const KDL::JntArray& arr) {
00448 KDL::Jacobian jac(arr.data.size());
00449
00450 jacsolver->JntToJac(arr,jac);
00451
00452 Eigen::JacobiSVD<Eigen::MatrixXd> svdsolver(jac.data);
00453 Eigen::MatrixXd singular_values = svdsolver.singularValues();
00454
00455 return singular_values.minCoeff()/singular_values.maxCoeff();
00456 }
00457
00458
00459 int TRAC_IK::CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const KDL::Twist& _bounds) {
00460
00461 if (!initialized) {
00462 ROS_ERROR("TRAC-IK was not properly initialized with a valid chain or limits. IK cannot proceed");
00463 return -1;
00464 }
00465
00466
00467 start_time = boost::posix_time::microsec_clock::local_time();
00468
00469 nl_solver->reset();
00470 iksolver->reset();
00471
00472 solutions.clear();
00473 errors.clear();
00474
00475
00476 bounds=_bounds;
00477
00478 std::vector<boost::shared_future<bool> > pending_data;
00479
00480 typedef boost::packaged_task<bool> task_t;
00481 boost::shared_ptr<task_t> task1 = boost::make_shared<task_t>(boost::bind(&TRAC_IK::runKDL, this, boost::cref(q_init), boost::cref(p_in)));
00482
00483 boost::shared_ptr<task_t> task2 = boost::make_shared<task_t>(boost::bind(&TRAC_IK::runNLOPT, this, boost::cref(q_init), boost::cref(p_in)));
00484
00485 boost::shared_future<bool> fut1(task1->get_future());
00486 boost::shared_future<bool> fut2(task2->get_future());
00487
00488
00489
00490
00491
00492
00493 pending_data.push_back(fut1);
00494 pending_data.push_back(fut2);
00495
00496 io_service.post(boost::bind(&task_t::operator(), task1));
00497 io_service.post(boost::bind(&task_t::operator(), task2));
00498
00499 boost::wait_for_all(pending_data.begin(), pending_data.end());
00500
00501 if (solutions.empty()) {
00502 q_out=q_init;
00503 return -3;
00504 }
00505
00506 switch (solvetype) {
00507 case Manip1:
00508 case Manip2:
00509 std::sort(errors.rbegin(),errors.rend());
00510 break;
00511 default:
00512 std::sort(errors.begin(),errors.end());
00513 break;
00514 }
00515
00516 q_out = solutions[errors[0].second];
00517
00518 return solutions.size();
00519 }
00520
00521
00522 TRAC_IK::~TRAC_IK(){
00523
00524 io_service.stop();
00525
00526
00527 try
00528 {
00529 threads.join_all();
00530 }
00531 catch ( ... ) {}
00532
00533 }
00534
00535 }