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 #include <trac_ik/nlopt_ik.hpp>
00032 #include <ros/ros.h>
00033 #include <limits>
00034 #include <boost/date_time.hpp>
00035 #include <trac_ik/dual_quaternion.h>
00036 #include <cmath>
00037
00038
00039
00040 namespace NLOPT_IK
00041 {
00042
00043 dual_quaternion targetDQ;
00044
00045 double minfunc(const std::vector<double>& x, std::vector<double>& grad, void* data)
00046 {
00047
00048
00049
00050
00051
00052 NLOPT_IK *c = (NLOPT_IK *) data;
00053
00054 return c->minJoints(x, grad);
00055 }
00056
00057 double minfuncDQ(const std::vector<double>& x, std::vector<double>& grad, void* data)
00058 {
00059
00060
00061
00062
00063 NLOPT_IK *c = (NLOPT_IK *) data;
00064
00065 std::vector<double> vals(x);
00066
00067 double jump = boost::math::tools::epsilon<float>();
00068 double result[1];
00069 c->cartDQError(vals, result);
00070
00071 if (!grad.empty())
00072 {
00073 double v1[1];
00074 for (uint i = 0; i < x.size(); i++)
00075 {
00076 double original = vals[i];
00077
00078 vals[i] = original + jump;
00079 c->cartDQError(vals, v1);
00080
00081 vals[i] = original;
00082 grad[i] = (v1[0] - result[0]) / (2 * jump);
00083 }
00084 }
00085
00086 return result[0];
00087 }
00088
00089
00090 double minfuncSumSquared(const std::vector<double>& x, std::vector<double>& grad, void* data)
00091 {
00092
00093
00094
00095
00096
00097 NLOPT_IK *c = (NLOPT_IK *) data;
00098
00099 std::vector<double> vals(x);
00100
00101 double jump = boost::math::tools::epsilon<float>();
00102 double result[1];
00103 c->cartSumSquaredError(vals, result);
00104
00105 if (!grad.empty())
00106 {
00107 double v1[1];
00108 for (uint i = 0; i < x.size(); i++)
00109 {
00110 double original = vals[i];
00111
00112 vals[i] = original + jump;
00113 c->cartSumSquaredError(vals, v1);
00114
00115 vals[i] = original;
00116 grad[i] = (v1[0] - result[0]) / (2.0 * jump);
00117 }
00118 }
00119
00120 return result[0];
00121 }
00122
00123
00124 double minfuncL2(const std::vector<double>& x, std::vector<double>& grad, void* data)
00125 {
00126
00127
00128
00129
00130
00131 NLOPT_IK *c = (NLOPT_IK *) data;
00132
00133 std::vector<double> vals(x);
00134
00135 double jump = boost::math::tools::epsilon<float>();
00136 double result[1];
00137 c->cartL2NormError(vals, result);
00138
00139 if (!grad.empty())
00140 {
00141 double v1[1];
00142 for (uint i = 0; i < x.size(); i++)
00143 {
00144 double original = vals[i];
00145
00146 vals[i] = original + jump;
00147 c->cartL2NormError(vals, v1);
00148
00149 vals[i] = original;
00150 grad[i] = (v1[0] - result[0]) / (2.0 * jump);
00151 }
00152 }
00153
00154 return result[0];
00155 }
00156
00157
00158
00159 void constrainfuncm(uint m, double* result, uint n, const double* x, double* grad, void* data)
00160 {
00161
00162
00163
00164
00165 NLOPT_IK *c = (NLOPT_IK *) data;
00166
00167 std::vector<double> vals(n);
00168
00169 for (uint i = 0; i < n; i++)
00170 {
00171 vals[i] = x[i];
00172 }
00173
00174 double jump = boost::math::tools::epsilon<float>();
00175
00176 c->cartSumSquaredError(vals, result);
00177
00178 if (grad != NULL)
00179 {
00180 std::vector<double> v1(m);
00181 for (uint i = 0; i < n; i++)
00182 {
00183 double o = vals[i];
00184 vals[i] = o + jump;
00185 c->cartSumSquaredError(vals, v1.data());
00186 vals[i] = o;
00187 for (uint j = 0; j < m; j++)
00188 {
00189 grad[j * n + i] = (v1[j] - result[j]) / (2 * jump);
00190 }
00191 }
00192 }
00193 }
00194
00195
00196 NLOPT_IK::NLOPT_IK(const KDL::Chain& _chain, const KDL::JntArray& _q_min, const KDL::JntArray& _q_max, double _maxtime, double _eps, OptType _type):
00197 chain(_chain), fksolver(_chain), maxtime(_maxtime), eps(std::abs(_eps)), TYPE(_type)
00198 {
00199 assert(chain.getNrOfJoints() == _q_min.data.size());
00200 assert(chain.getNrOfJoints() == _q_max.data.size());
00201
00202
00203
00204
00205 reset();
00206
00207 if (chain.getNrOfJoints() < 2)
00208 {
00209 ROS_WARN_THROTTLE(1.0, "NLOpt_IK can only be run for chains of length 2 or more");
00210 return;
00211 }
00212 opt = nlopt::opt(nlopt::LD_SLSQP, _chain.getNrOfJoints());
00213
00214 for (uint i = 0; i < chain.getNrOfJoints(); i++)
00215 {
00216 lb.push_back(_q_min(i));
00217 ub.push_back(_q_max(i));
00218 }
00219
00220 for (uint i = 0; i < chain.segments.size(); i++)
00221 {
00222 std::string type = chain.segments[i].getJoint().getTypeName();
00223 if (type.find("Rot") != std::string::npos)
00224 {
00225 if (_q_max(types.size()) >= std::numeric_limits<float>::max() &&
00226 _q_min(types.size()) <= std::numeric_limits<float>::lowest())
00227 types.push_back(KDL::BasicJointType::Continuous);
00228 else
00229 types.push_back(KDL::BasicJointType::RotJoint);
00230 }
00231 else if (type.find("Trans") != std::string::npos)
00232 types.push_back(KDL::BasicJointType::TransJoint);
00233 }
00234
00235 assert(types.size() == lb.size());
00236
00237 std::vector<double> tolerance(1, boost::math::tools::epsilon<float>());
00238 opt.set_xtol_abs(tolerance[0]);
00239
00240
00241 switch (TYPE)
00242 {
00243 case Joint:
00244 opt.set_min_objective(minfunc, this);
00245 opt.add_equality_mconstraint(constrainfuncm, this, tolerance);
00246 break;
00247 case DualQuat:
00248 opt.set_min_objective(minfuncDQ, this);
00249 break;
00250 case SumSq:
00251 opt.set_min_objective(minfuncSumSquared, this);
00252 break;
00253 case L2:
00254 opt.set_min_objective(minfuncL2, this);
00255 break;
00256 }
00257 }
00258
00259
00260 double NLOPT_IK::minJoints(const std::vector<double>& x, std::vector<double>& grad)
00261 {
00262
00263
00264
00265
00266 bool gradient = !grad.empty();
00267
00268 double err = 0;
00269 for (uint i = 0; i < x.size(); i++)
00270 {
00271 err += pow(x[i] - des[i], 2);
00272 if (gradient)
00273 grad[i] = 2.0 * (x[i] - des[i]);
00274 }
00275
00276 return err;
00277
00278 }
00279
00280
00281 void NLOPT_IK::cartSumSquaredError(const std::vector<double>& x, double error[])
00282 {
00283
00284
00285
00286
00287
00288 if (aborted || progress != -3)
00289 {
00290 opt.force_stop();
00291 return;
00292 }
00293
00294
00295 KDL::JntArray q(x.size());
00296
00297 for (uint i = 0; i < x.size(); i++)
00298 q(i) = x[i];
00299
00300 int rc = fksolver.JntToCart(q, currentPose);
00301
00302 if (rc < 0)
00303 ROS_FATAL_STREAM("KDL FKSolver is failing: " << q.data);
00304
00305 if (std::isnan(currentPose.p.x()))
00306 {
00307 ROS_ERROR("NaNs from NLOpt!!");
00308 error[0] = std::numeric_limits<float>::max();
00309 progress = -1;
00310 return;
00311 }
00312
00313 KDL::Twist delta_twist = KDL::diffRelative(targetPose, currentPose);
00314
00315 for (int i = 0; i < 6; i++)
00316 {
00317 if (std::abs(delta_twist[i]) <= std::abs(bounds[i]))
00318 delta_twist[i] = 0.0;
00319 }
00320
00321 error[0] = KDL::dot(delta_twist.vel, delta_twist.vel) + KDL::dot(delta_twist.rot, delta_twist.rot);
00322
00323 if (KDL::Equal(delta_twist, KDL::Twist::Zero(), eps))
00324 {
00325 progress = 1;
00326 best_x = x;
00327 return;
00328 }
00329 }
00330
00331
00332
00333 void NLOPT_IK::cartL2NormError(const std::vector<double>& x, double error[])
00334 {
00335
00336
00337
00338
00339
00340 if (aborted || progress != -3)
00341 {
00342 opt.force_stop();
00343 return;
00344 }
00345
00346 KDL::JntArray q(x.size());
00347
00348 for (uint i = 0; i < x.size(); i++)
00349 q(i) = x[i];
00350
00351 int rc = fksolver.JntToCart(q, currentPose);
00352
00353 if (rc < 0)
00354 ROS_FATAL_STREAM("KDL FKSolver is failing: " << q.data);
00355
00356
00357 if (std::isnan(currentPose.p.x()))
00358 {
00359 ROS_ERROR("NaNs from NLOpt!!");
00360 error[0] = std::numeric_limits<float>::max();
00361 progress = -1;
00362 return;
00363 }
00364
00365 KDL::Twist delta_twist = KDL::diffRelative(targetPose, currentPose);
00366
00367 for (int i = 0; i < 6; i++)
00368 {
00369 if (std::abs(delta_twist[i]) <= std::abs(bounds[i]))
00370 delta_twist[i] = 0.0;
00371 }
00372
00373 error[0] = std::sqrt(KDL::dot(delta_twist.vel, delta_twist.vel) + KDL::dot(delta_twist.rot, delta_twist.rot));
00374
00375 if (KDL::Equal(delta_twist, KDL::Twist::Zero(), eps))
00376 {
00377 progress = 1;
00378 best_x = x;
00379 return;
00380 }
00381 }
00382
00383
00384
00385
00386 void NLOPT_IK::cartDQError(const std::vector<double>& x, double error[])
00387 {
00388
00389
00390
00391
00392
00393 if (aborted || progress != -3)
00394 {
00395 opt.force_stop();
00396 return;
00397 }
00398
00399 KDL::JntArray q(x.size());
00400
00401 for (uint i = 0; i < x.size(); i++)
00402 q(i) = x[i];
00403
00404 int rc = fksolver.JntToCart(q, currentPose);
00405
00406 if (rc < 0)
00407 ROS_FATAL_STREAM("KDL FKSolver is failing: " << q.data);
00408
00409
00410 if (std::isnan(currentPose.p.x()))
00411 {
00412 ROS_ERROR("NaNs from NLOpt!!");
00413 error[0] = std::numeric_limits<float>::max();
00414 progress = -1;
00415 return;
00416 }
00417
00418 KDL::Twist delta_twist = KDL::diffRelative(targetPose, currentPose);
00419
00420 for (int i = 0; i < 6; i++)
00421 {
00422 if (std::abs(delta_twist[i]) <= std::abs(bounds[i]))
00423 delta_twist[i] = 0.0;
00424 }
00425
00426 math3d::matrix3x3<double> currentRotationMatrix(currentPose.M.data);
00427 math3d::quaternion<double> currentQuaternion = math3d::rot_matrix_to_quaternion<double>(currentRotationMatrix);
00428 math3d::point3d currentTranslation(currentPose.p.data);
00429 dual_quaternion currentDQ = dual_quaternion::rigid_transformation(currentQuaternion, currentTranslation);
00430
00431 dual_quaternion errorDQ = (currentDQ * !targetDQ).normalize();
00432 errorDQ.log();
00433 error[0] = 4.0f * dot(errorDQ, errorDQ);
00434
00435
00436 if (KDL::Equal(delta_twist, KDL::Twist::Zero(), eps))
00437 {
00438 progress = 1;
00439 best_x = x;
00440 return;
00441 }
00442 }
00443
00444
00445 int NLOPT_IK::CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const KDL::Twist _bounds, const KDL::JntArray& q_desired)
00446 {
00447
00448
00449
00450
00451
00452
00453
00454
00455
00456 boost::posix_time::ptime start_time = boost::posix_time::microsec_clock::local_time();
00457 boost::posix_time::time_duration diff;
00458
00459 bounds = _bounds;
00460 q_out = q_init;
00461
00462 if (chain.getNrOfJoints() < 2)
00463 {
00464 ROS_ERROR_THROTTLE(1.0, "NLOpt_IK can only be run for chains of length 2 or more");
00465 return -3;
00466 }
00467
00468 if (q_init.data.size() != types.size())
00469 {
00470 ROS_ERROR_THROTTLE(1.0, "IK seeded with wrong number of joints. Expected %d but got %d", (int)types.size(), (int)q_init.data.size());
00471 return -3;
00472 }
00473
00474 opt.set_maxtime(maxtime);
00475
00476
00477 double minf;
00478
00479 targetPose = p_in;
00480
00481 if (TYPE == 1)
00482 {
00483 math3d::matrix3x3<double> targetRotationMatrix(targetPose.M.data);
00484 math3d::quaternion<double> targetQuaternion = math3d::rot_matrix_to_quaternion<double>(targetRotationMatrix);
00485 math3d::point3d targetTranslation(targetPose.p.data);
00486 targetDQ = dual_quaternion::rigid_transformation(targetQuaternion, targetTranslation);
00487 }
00488
00489
00490
00491
00492
00493
00494
00495
00496
00497
00498 std::vector<double> x(chain.getNrOfJoints());
00499
00500 for (uint i = 0; i < x.size(); i++)
00501 {
00502 x[i] = q_init(i);
00503
00504 if (types[i] == KDL::BasicJointType::Continuous)
00505 continue;
00506
00507 if (types[i] == KDL::BasicJointType::TransJoint)
00508 {
00509 x[i] = std::min(x[i], ub[i]);
00510 x[i] = std::max(x[i], lb[i]);
00511 }
00512 else
00513 {
00514
00515
00516
00517 if (x[i] > ub[i])
00518 {
00519
00520 double diffangle = fmod(x[i] - ub[i], 2 * M_PI);
00521
00522 x[i] = ub[i] + diffangle - 2 * M_PI;
00523 }
00524
00525 if (x[i] < lb[i])
00526 {
00527
00528 double diffangle = fmod(lb[i] - x[i], 2 * M_PI);
00529
00530 x[i] = lb[i] - diffangle + 2 * M_PI;
00531 }
00532
00533 if (x[i] > ub[i])
00534 x[i] = (ub[i] + lb[i]) / 2.0;
00535 }
00536 }
00537
00538 best_x = x;
00539 progress = -3;
00540
00541 std::vector<double> artificial_lower_limits(lb.size());
00542
00543 for (uint i = 0; i < lb.size(); i++)
00544 if (types[i] == KDL::BasicJointType::Continuous)
00545 artificial_lower_limits[i] = best_x[i] - 2 * M_PI;
00546 else if (types[i] == KDL::BasicJointType::TransJoint)
00547 artificial_lower_limits[i] = lb[i];
00548 else
00549 artificial_lower_limits[i] = std::max(lb[i], best_x[i] - 2 * M_PI);
00550
00551 opt.set_lower_bounds(artificial_lower_limits);
00552
00553 std::vector<double> artificial_upper_limits(lb.size());
00554
00555 for (uint i = 0; i < ub.size(); i++)
00556 if (types[i] == KDL::BasicJointType::Continuous)
00557 artificial_upper_limits[i] = best_x[i] + 2 * M_PI;
00558 else if (types[i] == KDL::BasicJointType::TransJoint)
00559 artificial_upper_limits[i] = ub[i];
00560 else
00561 artificial_upper_limits[i] = std::min(ub[i], best_x[i] + 2 * M_PI);
00562
00563 opt.set_upper_bounds(artificial_upper_limits);
00564
00565 if (q_desired.data.size() == 0)
00566 {
00567 des = x;
00568 }
00569 else
00570 {
00571 des.resize(x.size());
00572 for (uint i = 0; i < des.size(); i++)
00573 des[i] = q_desired(i);
00574 }
00575
00576 try
00577 {
00578 opt.optimize(x, minf);
00579 }
00580 catch (...)
00581 {
00582 }
00583
00584 if (progress == -1)
00585 progress = -3;
00586
00587
00588 if (!aborted && progress < 0)
00589 {
00590
00591 double time_left;
00592 diff = boost::posix_time::microsec_clock::local_time() - start_time;
00593 time_left = maxtime - diff.total_nanoseconds() / 1000000000.0;
00594
00595 while (time_left > 0 && !aborted && progress < 0)
00596 {
00597
00598 for (uint i = 0; i < x.size(); i++)
00599 x[i] = fRand(artificial_lower_limits[i], artificial_upper_limits[i]);
00600
00601 opt.set_maxtime(time_left);
00602
00603 try
00604 {
00605 opt.optimize(x, minf);
00606 }
00607 catch (...) {}
00608
00609 if (progress == -1)
00610 progress = -3;
00611
00612 diff = boost::posix_time::microsec_clock::local_time() - start_time;
00613 time_left = maxtime - diff.total_nanoseconds() / 1000000000.0;
00614 }
00615 }
00616
00617
00618 for (uint i = 0; i < x.size(); i++)
00619 {
00620 q_out(i) = best_x[i];
00621 }
00622
00623 return progress;
00624
00625 }
00626
00627
00628 }