34 #include <boost/date_time.hpp> 45 double minfunc(
const std::vector<double>& x, std::vector<double>& grad,
void* data)
54 return c->minJoints(x, grad);
57 double minfuncDQ(
const std::vector<double>& x, std::vector<double>& grad,
void* data)
65 std::vector<double> vals(x);
67 double jump = boost::math::tools::epsilon<float>();
69 c->cartDQError(vals, result);
74 for (uint i = 0; i < x.size(); i++)
76 double original = vals[i];
78 vals[i] = original + jump;
79 c->cartDQError(vals, v1);
82 grad[i] = (v1[0] - result[0]) / (2 * jump);
90 double minfuncSumSquared(
const std::vector<double>& x, std::vector<double>& grad,
void* data)
99 std::vector<double> vals(x);
101 double jump = boost::math::tools::epsilon<float>();
103 c->cartSumSquaredError(vals, result);
108 for (uint i = 0; i < x.size(); i++)
110 double original = vals[i];
112 vals[i] = original + jump;
113 c->cartSumSquaredError(vals, v1);
116 grad[i] = (v1[0] - result[0]) / (2.0 * jump);
124 double minfuncL2(
const std::vector<double>& x, std::vector<double>& grad,
void* data)
133 std::vector<double> vals(x);
135 double jump = boost::math::tools::epsilon<float>();
137 c->cartL2NormError(vals, result);
142 for (uint i = 0; i < x.size(); i++)
144 double original = vals[i];
146 vals[i] = original + jump;
147 c->cartL2NormError(vals, v1);
150 grad[i] = (v1[0] - result[0]) / (2.0 * jump);
159 void constrainfuncm(uint m,
double* result, uint n,
const double* x,
double* grad,
void* data)
167 std::vector<double> vals(n);
169 for (uint i = 0; i < n; i++)
174 double jump = boost::math::tools::epsilon<float>();
176 c->cartSumSquaredError(vals, result);
180 std::vector<double> v1(m);
181 for (uint i = 0; i < n; i++)
185 c->cartSumSquaredError(vals, v1.data());
187 for (uint j = 0; j < m; j++)
189 grad[j * n + i] = (v1[j] - result[j]) / (2 * jump);
197 chain(_chain), fksolver(_chain), maxtime(_maxtime), eps(
std::
abs(_eps)), TYPE(_type)
199 assert(chain.getNrOfJoints() == _q_min.
data.size());
200 assert(chain.getNrOfJoints() == _q_max.
data.size());
207 if (chain.getNrOfJoints() < 2)
209 ROS_WARN_THROTTLE(1.0,
"NLOpt_IK can only be run for chains of length 2 or more");
214 for (uint i = 0; i < chain.getNrOfJoints(); i++)
216 lb.push_back(_q_min(i));
217 ub.push_back(_q_max(i));
220 for (uint i = 0; i < chain.segments.size(); i++)
222 std::string type = chain.segments[i].getJoint().getTypeName();
223 if (type.find(
"Rot") != std::string::npos)
225 if (_q_max(types.size()) >= std::numeric_limits<float>::max() &&
226 _q_min(types.size()) <= std::numeric_limits<float>::lowest())
231 else if (type.find(
"Trans") != std::string::npos)
235 assert(types.size() == lb.size());
237 std::vector<double> tolerance(1, boost::math::tools::epsilon<float>());
238 opt.set_xtol_abs(tolerance[0]);
244 opt.set_min_objective(
minfunc,
this);
260 double NLOPT_IK::minJoints(
const std::vector<double>& x, std::vector<double>& grad)
266 bool gradient = !grad.empty();
269 for (uint i = 0; i < x.size(); i++)
271 err +=
pow(x[i] - des[i], 2);
273 grad[i] = 2.0 * (x[i] - des[i]);
281 void NLOPT_IK::cartSumSquaredError(
const std::vector<double>& x,
double error[])
288 if (aborted || progress != -3)
297 for (uint i = 0; i < x.size(); i++)
300 int rc = fksolver.JntToCart(q, currentPose);
305 if (std::isnan(currentPose.p.x()))
308 error[0] = std::numeric_limits<float>::max();
315 for (
int i = 0; i < 6; i++)
317 if (std::abs(delta_twist[i]) <= std::abs(bounds[i]))
318 delta_twist[i] = 0.0;
333 void NLOPT_IK::cartL2NormError(
const std::vector<double>& x,
double error[])
340 if (aborted || progress != -3)
348 for (uint i = 0; i < x.size(); i++)
351 int rc = fksolver.JntToCart(q, currentPose);
357 if (std::isnan(currentPose.p.x()))
360 error[0] = std::numeric_limits<float>::max();
367 for (
int i = 0; i < 6; i++)
369 if (std::abs(delta_twist[i]) <= std::abs(bounds[i]))
370 delta_twist[i] = 0.0;
386 void NLOPT_IK::cartDQError(
const std::vector<double>& x,
double error[])
393 if (aborted || progress != -3)
401 for (uint i = 0; i < x.size(); i++)
404 int rc = fksolver.JntToCart(q, currentPose);
410 if (std::isnan(currentPose.p.x()))
413 error[0] = std::numeric_limits<float>::max();
420 for (
int i = 0; i < 6; i++)
422 if (std::abs(delta_twist[i]) <= std::abs(bounds[i]))
423 delta_twist[i] = 0.0;
433 error[0] = 4.0f *
dot(errorDQ, errorDQ);
456 boost::posix_time::ptime start_time = boost::posix_time::microsec_clock::local_time();
457 boost::posix_time::time_duration
diff;
462 if (chain.getNrOfJoints() < 2)
468 if (q_init.
data.size() != types.size())
470 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());
474 opt.set_maxtime(maxtime);
498 std::vector<double> x(chain.getNrOfJoints());
500 for (uint i = 0; i < x.size(); i++)
509 x[i] = std::min(x[i], ub[i]);
510 x[i] = std::max(x[i], lb[i]);
520 double diffangle = fmod(x[i] - ub[i], 2 *
M_PI);
522 x[i] = ub[i] + diffangle - 2 *
M_PI;
528 double diffangle = fmod(lb[i] - x[i], 2 *
M_PI);
530 x[i] = lb[i] - diffangle + 2 *
M_PI;
534 x[i] = (ub[i] + lb[i]) / 2.0;
541 std::vector<double> artificial_lower_limits(lb.size());
543 for (uint i = 0; i < lb.size(); i++)
545 artificial_lower_limits[i] = best_x[i] - 2 *
M_PI;
547 artificial_lower_limits[i] = lb[i];
549 artificial_lower_limits[i] = std::max(lb[i], best_x[i] - 2 * M_PI);
551 opt.set_lower_bounds(artificial_lower_limits);
553 std::vector<double> artificial_upper_limits(lb.size());
555 for (uint i = 0; i < ub.size(); i++)
557 artificial_upper_limits[i] = best_x[i] + 2 *
M_PI;
559 artificial_upper_limits[i] = ub[i];
561 artificial_upper_limits[i] = std::min(ub[i], best_x[i] + 2 * M_PI);
563 opt.set_upper_bounds(artificial_upper_limits);
565 if (q_desired.
data.size() == 0)
571 des.resize(x.size());
572 for (uint i = 0; i < des.size(); i++)
573 des[i] = q_desired(i);
578 opt.optimize(x, minf);
588 if (!aborted && progress < 0)
592 diff = boost::posix_time::microsec_clock::local_time() - start_time;
593 time_left = maxtime - diff.total_nanoseconds() / 1000000000.0;
595 while (time_left > 0 && !aborted && progress < 0)
598 for (uint i = 0; i < x.size(); i++)
599 x[i] = fRand(artificial_lower_limits[i], artificial_upper_limits[i]);
601 opt.set_maxtime(time_left);
605 opt.optimize(x, minf);
612 diff = boost::posix_time::microsec_clock::local_time() - start_time;
613 time_left = maxtime - diff.total_nanoseconds() / 1000000000.0;
618 for (uint i = 0; i < x.size(); i++)
620 q_out(i) = best_x[i];
double dot(const dual_quaternion &a, const dual_quaternion &b)
double minfuncSumSquared(const std::vector< double > &x, std::vector< double > &grad, void *data)
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
IMETHOD Twist diffRelative(const Frame &F_a_b1, const Frame &F_a_b2, double dt=1)
static dual_quaternion rigid_transformation(const quaternion< double > &r, const point3d &t)
doubleAcc dot(const VectorAcc &lhs, const VectorAcc &rhs)
double minfunc(const std::vector< double > &x, std::vector< double > &grad, void *data)
IMETHOD bool Equal(const FrameAcc &r1, const FrameAcc &r2, double eps=epsilon)
#define ROS_FATAL_STREAM(args)
#define ROS_WARN_THROTTLE(period,...)
#define ROS_ERROR_THROTTLE(period,...)
unsigned int getNrOfJoints() const
void constrainfuncm(uint m, double *result, uint n, const double *x, double *grad, void *data)
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
INLINE Rall1d< T, V, S > abs(const Rall1d< T, V, S > &x)
void normalize(quaternion< T > &q)
double minfuncDQ(const std::vector< double > &x, std::vector< double > &grad, void *data)
double minfuncL2(const std::vector< double > &x, std::vector< double > &grad, void *data)