trajectory.cpp
Go to the documentation of this file.
1 
9 /*****************************************************************************
10  ** Includes
11  *****************************************************************************/
12 
13 #include <ecl/linear_algebra.hpp> // has to be first (eigen stdvector defn).
14 #include "../../include/ecl/manipulators/waypoint.hpp"
15 #include "../../include/ecl/manipulators/trajectory.hpp"
18 #include <ecl/math/simple.hpp>
19 
20 /*****************************************************************************
21  ** Debug Macros
22  *****************************************************************************/
23 
24 //#define DEBUG_LINEAR_INTERPOLATION
25 /*****************************************************************************
26  ** Namespaces
27  *****************************************************************************/
28 
29 namespace ecl
30 {
31 
32 /*****************************************************************************
33  ** Implementation [Trajectory][QuinticTensionSplineInterpolation]
34  *****************************************************************************/
35 
37 {
38  bool result;
39  unsigned int n = waypoints.size() - 1; // n = number of segments
40 
41  // who the hell made the constraint that this should be 5, shouldn't we only need 3 since we calculate 2 more pseudo points?
43  n+1 >= 5,
44  StandardException(LOC,ConfigurationError,"Not enough waypoints for a tension spline interpolation (must be >= 5)."));
45 
46  result = validateWaypoints(5);
48  result,
49  StandardException(LOC,ConfigurationError,"Not all the waypoint maximum rates have been specified correctly (must be > 0.0)."));
50 
51  result = initialiseWaypointDurations();
52  ecl_assert_throw( result,
53  StandardException(LOC,ConfigurationError,"A waypoint was configured with a zero duration."));
54 
55  /******************************************
56  ** Reserve Spline Storage Space
57  *******************************************/
58  clearSplines(); // Clean up any pre-existing definition.
59  for (unsigned int j = 0; j < dimension(); ++j)
60  {
61  spline_functions[j].resize(3, NULL);
62  }
63  Array<TensionSpline> tension_splines(dimension());
64  Array<QuinticPolynomial> leading_quintics(dimension()), trailing_quintics(dimension());
65 
66  /******************************************
67  ** Roughly Generate Tension Spline
68  *******************************************/
69  bool splines_constrained = false;
70  while (!splines_constrained)
71  {
72  tension_splines = generateTensionSplines(tension, 0.0);
73  /*********************
74  ** Check Max Accel
75  **********************/
76  Array<double> domain = tension_splines[0].domain();
77  splines_constrained = true; // This changes to false if we break the max accel constraint
78  // - tension splines have high accelerations at the joins.
79  // - inbetween the joins, the acceleration goes towards zero.
80  // - so we just check the size of the acceleration at the joins to find trouble spots.
81  for (unsigned int i = 1; i < domain.size() - 1; ++i)
82  { // Natural spline, first and last accelerations are always zero, so dont worry about them
83  for (unsigned int j = 0; j < dimension(); ++j)
84  {
85  double accel = fabs(tension_splines[j].dderivative(domain[i]));
86  /*********************
87  ** Debugging
88  **********************/
89 // std::cout << "Accel checking" << std::endl;
90 // std::cout << " Domain: " << domain << std::endl;
91 // std::cout << " Accel[" << i << "," << j << "]: " << accel << std::endl;
92 // sleep(1);
93  if (accel > max_accelerations[j])
94  {
95  splines_constrained = false;
96  double slope_before = fabs(
97  (waypoints[i].angles()[j] - waypoints[i - 1].angles()[j]) / waypoints[i - 1].duration());
98  double slope_after = fabs(
99  (waypoints[i + 1].angles()[j] - waypoints[i].angles()[j]) / waypoints[i].duration());
100 // std::cout << " Slope_Before[" << i << "," << j << "]: " << slope_before << std::endl;
101 // std::cout << " Slope_After [" << i << "," << j << "]: " << slope_after << std::endl;
102  if (slope_before > slope_after)
103  {
104  waypoints[i - 1].duration(waypoints[i - 1].duration() * 1.1); // 10% increase
105  }
106  else
107  {
108  waypoints[i].duration(waypoints[i].duration() * 1.1); // 10% increase
109  }
110 // i = domain.size(); // Force it to restart <-- This doesn't actually work so well - dampen the whole curve at once instead of gradually from one end!
111  break;
112  }
113  }
114  }
115  }
116  /******************************************
117  ** Check rates are set for head/tail
118  *******************************************/
119  // Note that we may yet change values[1] and values[n+1] when fixing the pseudo points below
120  // Set them all to zero (default option, i.e. starting at rest).
121  if (!waypoints[0].rates_configured())
122  {
123  waypoints[0].rates() = WayPoint<JointAngles>::JointDataArray::Constant(waypoints[0].dimension(), 0.0);
124  }
125  if (!waypoints[n].rates_configured())
126  {
127  waypoints[n].rates() = WayPoint<JointAngles>::JointDataArray::Constant(waypoints[n].dimension(), 0.0);
128  }
129 
130  /******************************************
131  ** Make the pre pseudo point.
132  *******************************************/
133  double leading_quintic_time = 0.0;
134  bool quintic_constrained = false;
135  while (!quintic_constrained)
136  {
137  quintic_constrained = true;
138  for (unsigned int i = 1; i <= 5; ++i)
139  {
140  double t = i * waypoints[0].duration() / 10;
141  // move the tension spline to the right, i.e. give us some space to insert a quintic
142  tension_splines = generateTensionSplines(tension, t); // t <-- is the initial time to start the tension spline
143  for (unsigned int j = 0; j < dimension(); ++j)
144  {
145  // find the right side boundary conditions for the quintic we want to insert
146  double y_dot = tension_splines[j].derivative(2 * t);
147  double y = tension_splines[j](2 * t);
148  // the left side boundary conditions for the quintic
149  double y_0 = waypoints[0].angles()[j];
150  double y_0_dot = waypoints[0].rates()[j];
151  leading_quintics[j] = QuinticPolynomial::Interpolation(0.0, y_0, y_0_dot, 0.0, 2 * t, y, y_dot, 0.0);
152 
153  /*********************
154  ** Debugging
155  **********************/
156 // std::cout << "Pre Pseudo Point" << std::endl;
157 // std::cout << " Domain: " << tension_splines[0].domain() << std::endl;
158 // std::cout << " y[" << i << "," << j << "] : " << y << std::endl;
159 // std::cout << " y_dot[" << i << "," << j << "] : " << ydot << std::endl;
160 // double accel_max = fabs( Maximum<CubicPolynomial>()(0.0,2*t,leading_quintics[j].derivative().derivative()));
161 // if ( accel_max < fabs( Minimum<CubicPolynomial>()(0.0,2*t,leading_quintics[j].derivative().derivative())) ) {
162 // accel_max = fabs( Minimum<CubicPolynomial>()(0.0,2*t,leading_quintics[j].derivative().derivative()));
163 // }
164 // std::cout << " accel[" << i << "," << j << "] : " << accel_max << std::endl;
165 // sleep(1);
166  if ((fabs(ecl::Maximum<CubicPolynomial>()(0.0, 2 * t, leading_quintics[j].derivative().derivative()))
167  < fabs(max_accelerations[j]))
168  && (fabs(ecl::Minimum<CubicPolynomial>()(0.0, 2 * t, leading_quintics[j].derivative().derivative()))
169  < fabs(max_accelerations[j])))
170  {
171  if (j == dimension() - 1)
172  { // all joints are constrained, great!
173  leading_quintic_time = 2 * t;
174  // Everything done, force it to completely bail out of these loops.
175  quintic_constrained = true;
176  i = 5;
177  }
178  }
179  else
180  { // failed to constrain for this i value.
181  if (i == 5)
182  { // If we get here, even up to half the length of the segment has failed.
183  quintic_constrained = false;
184  }
185  break;
186  }
187  }
188  if (!quintic_constrained)
189  { // give up, go back to start of while loop with increased duration
190 // std::cout << "Quintic unconstrained, increasing the first duration : " << waypoints[0].duration() << std::endl;
191  waypoints[0].duration(waypoints[0].duration() * 1.1); // 10% increase
192  break; // from the for loop
193  }
194  }
195  }
196 
197  /******************************************
198  ** Make the post pseudo point.
199  *******************************************/
200  double trailing_quintic_time_0 = 0.0;
201  double trailing_quintic_time_f = 0.0;
202  quintic_constrained = false;
203  while (!quintic_constrained)
204  {
205  quintic_constrained = true;
206  tension_splines = generateTensionSplines(tension, leading_quintic_time / 2);
207  for (unsigned int i = 1; i <= 5; ++i)
208  {
209  double t = i * waypoints[n - 1].duration() / 10;
210  double t_f = tension_splines[0].domain().back();
211  for (unsigned int j = 0; j < dimension(); ++j)
212  {
213  double y_dot = tension_splines[j].derivative(t_f - t);
214  double y = tension_splines[j](t_f - t);
215  double y_f = waypoints[n].angles()[j];
216  double y_f_dot = waypoints[n].rates()[j];
217  trailing_quintics[j] = QuinticPolynomial::Interpolation(t_f - t, y, y_dot, 0.0, t_f + t, y_f, y_f_dot, 0.0);
218 
219  /*********************
220  ** Debugging
221  **********************/
222 // std::cout << "Post Pseudo Point" << std::endl;
223 // std::cout << " Domain: " << tension_splines[0].domain() << std::endl;
224 // std::cout << " y[" << i << "," << j << "] : " << y << std::endl;
225 // std::cout << " y_dot[" << i << "," << j << "] : " << ydot << std::endl;
226 // double accel_max = fabs( Maximum<CubicPolynomial>()(t_f-t,t_f+t,trailing_quintics[j].derivative().derivative()));
227 // if ( accel_max < fabs( Minimum<CubicPolynomial>()(t_f-t,t_f+t,trailing_quintics[j].derivative().derivative())) ) {
228 // accel_max = fabs( Minimum<CubicPolynomial>()(t_f-t,t_f+t,trailing_quintics[j].derivative().derivative()));
229 // }
230 // std::cout << " accel[" << i << "," << j << "] : " << accel_max << std::endl;
231 // sleep(1);
232  if ((fabs(Maximum<CubicPolynomial>()(t_f - t, t_f + t, trailing_quintics[j].derivative().derivative()))
233  < fabs(max_accelerations[j]))
234  && (fabs(Minimum<CubicPolynomial>()(t_f - t, t_f + t, trailing_quintics[j].derivative().derivative()))
235  < fabs(max_accelerations[j])))
236  {
237  if (j == dimension() - 1)
238  { // all joints are constrained, great!
239  trailing_quintic_time_0 = tension_splines[j].domain().back() - t;
240  trailing_quintic_time_f = tension_splines[j].domain().back() + t;
241  // Everything done, force it to completely bail out of these loops.
242  quintic_constrained = true;
243  i = 5;
244  }
245  }
246  else
247  { // failed to constrain for this i value.
248  if (i == 5)
249  { // If we get here, even up to half the length of the segment has failed.
250  quintic_constrained = false;
251  }
252  break;
253  }
254  }
255  if (!quintic_constrained)
256  { // give up, go back to start of while loop with increased duration
257  waypoints[n - 1].duration(waypoints[n - 1].duration() * 1.1); // 10% increase
258  break;
259  }
260  }
261  }
262 
263  /*********************
264  ** Debugging
265  **********************/
266 // std::cout << "Leading Quintic Time :" << leading_quintic_time << std::endl;
267 // std::cout << "Trailing Quintic Time:" << trailing_quintic_time_0 << " " << trailing_quintic_time_f << std::endl;
268  /******************************************
269  ** Finalise
270  *******************************************/
271  trajectory_duration = trailing_quintic_time_f;
272  for (unsigned int j = 0; j < dimension(); ++j)
273  {
274  spline_functions[j][0] = new SplineFunction<QuinticPolynomial>(0.0, leading_quintic_time, leading_quintics[j]);
275  spline_functions[j][1] = new SplineFunction<TensionSpline>(leading_quintic_time, trailing_quintic_time_0,
276  tension_splines[j]);
277  spline_functions[j][2] = new SplineFunction<QuinticPolynomial>(trailing_quintic_time_0, trailing_quintic_time_f,
278  trailing_quintics[j]);
279  }
280 }
281 
283 {
284  if (!validateWaypoints(2))
285  {
287  "Not all the waypoint maximum rates have been specified correctly (must be > 0.0).");
288  }
289  if (!initialiseWaypointDurations())
290  {
291  throw StandardException(LOC, ConfigurationError, "A waypoint was configured with a zero duration.");
292  }
293 
294  /******************************************
295  ** Reserve Spline Storage Space
296  *******************************************/
297  clearSplines(); // Clean up any pre-existing definition.
298  for (unsigned int j = 0; j < dimension(); ++j)
299  {
300  spline_functions[j].resize(1, NULL);
301  }
302  Array<SmoothLinearSpline> splines(dimension());
303 
304  /******************************************
305  ** Generate Splines
306  *******************************************/
307  bool splines_constrained = false;
308  int n = waypoints.size() - 1;
309  while (!splines_constrained)
310  {
311  try
312  {
313  splines = generateLinearSplines();
314  splines_constrained = true;
315 #ifdef DEBUG_LINEAR_INTERPOLATION
316  std::cout << "Linear Interpolation: spline generation success" << std::endl;
317 #endif
318  }
319  catch (DataException<int> &e)
320  {
321  /*********************
322  ** Stretch Waypoints
323  **********************/
324  if (e.data() <= 0)
325  {
326 #ifdef DEBUG_LINEAR_INTERPOLATION
327  std::cout << "Linear Interpolation: spline generation failed trying to create pre-pseudo, stretching first segment" << std::endl;
328 #endif
329  waypoints[0].duration(waypoints[0].duration() * 1.1); // 10% increase to w_{0}-w_{1} duration
330  }
331  else if (e.data() == 1)
332  { // error at corner prepseudo-w0-w1
333 #ifdef DEBUG_LINEAR_INTERPOLATION
334  std::cout << "Linear Interpolation: spline generation failed, stretching at corner " << e.data() << std::endl;
335 #endif
336  waypoints[0].duration(waypoints[0].duration() * 1.1); // 10% increase to w_{0}-w_{1} duration
337  }
338  else if (e.data() >= n + 1)
339  { // error at corner w_{n-1}-w_{n}-postpseudo
340 #ifdef DEBUG_LINEAR_INTERPOLATION
341  std::cout << "Linear Interpolation: spline generation failed, stretching at corner " << e.data() << std::endl;
342 #endif
343  waypoints[n - 1].duration(waypoints[n - 1].duration() * 1.1); // 10% increase to w_{n-1}-w_{n} duration
344  }
345  else if (e.data() >= n + 2)
346  {
347  // occurs when trying to create the post-pseudo point
348  waypoints[n - 1].duration(waypoints[n - 1].duration() * 1.1); // 10% increase to w_{n-1}-w_{n} duration
349 #ifdef DEBUG_LINEAR_INTERPOLATION
350  std::cout << "Linear Interpolation: spline generation failed trying to create post-pseudo, stretching last segment" << std::endl;
351 #endif
352  }
353  else
354  {
355 #ifdef DEBUG_LINEAR_INTERPOLATION
356  std::cout << "Linear Interpolation: spline generation failed, stretching at corner " << e.data() << std::endl;
357 #endif
358  waypoints[e.data() - 2].duration(waypoints[e.data() - 2].duration() * 1.05); // 5% increase on either side
359  waypoints[e.data() - 1].duration(waypoints[e.data() - 1].duration() * 1.05); // 5% increase on either side
360  }
361  }
362  }
363 
364  /******************************************
365  ** Finalise
366  *******************************************/
367  trajectory_duration = splines[0].domain().back() - splines[0].domain().front();
368  for (unsigned int j = 0; j < dimension(); ++j)
369  {
370  spline_functions[j][0] = new SplineFunction<SmoothLinearSpline>(0.0, splines[j].domain().back(), splines[j]);
371  }
372 }
373 
374 /*****************************************************************************
375  ** Implementation [Trajectory][Access]
376  *****************************************************************************/
377 
378 double Trajectory<JointAngles>::operator ()(const unsigned int& joint, const double& time)
379 
380 {
381 
382  double t_f = spline_functions[joint][spline_functions[joint].size() - 1]->domain()[1];
383  ecl_assert_throw( ( time >= 0.0 ) && ( time <= t_f + 0.0001 ), StandardException(LOC,OutOfRangeError));
384  unsigned int i;
385  for (i = 0; i < spline_functions[joint].size(); ++i)
386  {
387  if (time <= spline_functions[joint][i]->domain()[1])
388  {
389  return (*(spline_functions[joint][i]))(time);
390  }
391  }
392  // Sometimes machine precision can kill off some of the inequality arguments above (like e^{-16} error). Fallback:
393  return (*(spline_functions[joint][spline_functions[joint].size() - 1]))(t_f);
394 }
395 
396 double Trajectory<JointAngles>::derivative(const unsigned int& joint, const double& time)
397 
398 {
399 
400  double t_f = spline_functions[joint][spline_functions[joint].size() - 1]->domain()[1];
401  ecl_assert_throw( ( time >= 0.0 ) && ( time <= t_f + 0.0001 ), StandardException(LOC,OutOfRangeError));
402  unsigned int i;
403  for (i = 0; i < spline_functions[joint].size(); ++i)
404  {
405  if (time <= spline_functions[joint][i]->domain()[1])
406  {
407  return spline_functions[joint][i]->derivative(time);
408  break;
409  }
410  }
411  // Sometimes machine precision can kill off some of the inequality arguments above (like e^{-16} error). Fallback:
412  return spline_functions[joint][spline_functions[joint].size() - 1]->derivative(t_f);
413 }
414 
415 double Trajectory<JointAngles>::dderivative(const unsigned int& joint, const double& time)
416 
417 {
418 
419  double t_f = spline_functions[joint][spline_functions[joint].size() - 1]->domain()[1];
420  ecl_assert_throw( ( time >= 0.0 ) && ( time <= t_f + 0.0001 ), StandardException(LOC,OutOfRangeError));
421  unsigned int i;
422  for (i = 0; i < spline_functions[joint].size(); ++i)
423  {
424  if (time <= spline_functions[joint][i]->domain()[1])
425  {
426  return spline_functions[joint][i]->dderivative(time);
427  break;
428  }
429  }
430  // Sometimes machine precision can kill off some of the inequality arguments above (like e^{-16} error). Fallback:
431  return spline_functions[joint][spline_functions[joint].size() - 1]->dderivative(t_f);
432 }
433 
434 /*****************************************************************************
435  ** Implementation [Trajectory][Private]
436  *****************************************************************************/
437 
438 bool Trajectory<JointAngles>::validateWaypoints(unsigned int min_no_waypoints)
439 {
440 
441  unsigned int n = waypoints.size() - 1; // n = number of segments
442  if (n + 1 < min_no_waypoints)
443  {
444  return false;
445  }
446 
447  for (unsigned int i = 0; i < n; ++i)
448  { // Dont care about the last waypoint w_n
449  for (unsigned int j = 0; j < waypoints[i].nominalRates().size(); ++j)
450  {
451  if (waypoints[i].nominalRates()[j] <= 0.0)
452  {
453  return false;
454  }
455  }
456  }
457  return true;
458 }
459 
461 {
462 
463  unsigned int n = waypoints.size() - 1; // n = number of segments
464 
465  // Waypoint durations are often not configured and default to 0.0
466 
467  // Here we check the nominal rates and angle differences to automatically guess a
468  // duration. If the checks are ok, and this is bigger than the configured
469  // waypoint duration, then replace the waypoint duration with this calculation.
470  for (unsigned int i = 0; i < n; ++i)
471  { // Dont need to worry about the w_n's duration.
472  double max_duration = 0.0;
473  for (unsigned int j = 0; j < dimension(); ++j)
474  {
475  double distance = fabs(waypoints[i + 1].angles()[j] - waypoints[i].angles()[j]);
476  if (waypoints[i].nominalRates()[j] != 0.0)
477  {
478  double segment_duration = distance / waypoints[i].nominalRates()[j]; // Time = Distance/Velocity
479  if (segment_duration > max_duration)
480  {
481  max_duration = segment_duration;
482  }
483  }
484  }
485  if (max_duration > waypoints[i].duration())
486  {
487  waypoints[i].duration(max_duration);
488  }
489  if (waypoints[i].duration() == 0.0)
490  {
491  return false;
492  }
493  }
494  return true;
495 }
496 
498 {
499  for (unsigned int joint = 0; joint < dimension(); ++joint)
500  {
501  for (unsigned int function = 0; function < spline_functions[joint].size(); ++function)
502  {
503  if (spline_functions[joint][function] != NULL)
504  {
505  delete spline_functions[joint][function];
506  spline_functions[joint][function] = NULL;
507  }
508  }
509  spline_functions[joint].clear();
510  }
511 }
512 
514 {
515  double total_time = 0.0;
516 // std::cout << "Durations: ";
517  for (unsigned int i = 0; i < waypoints.size() - 1; ++i)
518  {
519  total_time += waypoints[i].duration();
520 // std::cout << waypoints[i].duration() << " ";
521  }
522 // std::cout << std::endl;
523  trajectory_duration = total_time;
524 }
525 
527 {
528  // n = number of segments
529  // n+1 = number of input waypoints
530  // n+3 = number of waypoints (inc. pre-post pseudo)
531 
532  // This is a bit different from the cubic as we don't use this in a combo interpolater.
533  Array<SmoothLinearSpline> splines(dimension());
534  unsigned int n = waypoints.size() - 1; // n = number of segments
535  Array<double> waypoint_times(n + 3), values(n + 3); // Including pre and post points
536 
537  /******************************************
538  ** Check rates are set for head/tail
539  *******************************************/
540  // Note that we may yet change values[1] and values[n+1] when fixing the pseudo points below
541  // Set them all to zero (default option, i.e. starting at rest).
542  if (!waypoints[0].rates_configured())
543  {
544  waypoints[0].rates() = WayPoint<JointAngles>::JointDataArray::Constant(waypoints[0].dimension(), 0.0);
545  }
546  if (!waypoints[n].rates_configured())
547  {
548  waypoints[n].rates() = WayPoint<JointAngles>::JointDataArray::Constant(waypoints[n].dimension(), 0.0);
549  }
550 
551  /******************************************
552  ** Make the pre pseudo point.
553  *******************************************/
554  /*
555  * Pull back the first waypoint, find intersection of initial tangent line and the nominal rate line.
556  * Why? This lets us ensure the first segment is of the specified velocity, and the second segment will
557  * fall the correct between nominal rates required to get to w_1.
558  *
559  * x_
560  * ^ \__
561  * / \
562  * o ------ o
563  * /
564  * /
565  * x
566  *
567  * - diagonal lines : nominal rate slopes
568  * - x : possible pseudo waypoints (at intersection of initial velocity line and nominal rate line)
569  *
570  * Basic process:
571  *
572  * - pullback a bit
573  * - get intersections as above
574  * - find minimum time intersection time (t_first_duration)
575  * - synchronise a pseudo waypoint at that time on the initial tangents for each joint (only 1 of these will be an actual intersection point)
576  * - check acceleration constraints of quintics for this waypoint at each joint
577  * - if fail, pullback again, if success, done!
578  */
579  std::vector<LinearFunction> initial_tangents; // these are the lines from potential pseudo point to w_1, our eventual pseudo point must lie on it.
580  std::vector<double> initial_angles, initial_rates;
581  for (unsigned int j = 0; j < dimension(); ++j)
582  {
583  initial_angles.push_back(waypoints[0].angles()[j]);
584  initial_rates.push_back(waypoints[0].rates()[j]);
585  initial_tangents.push_back(LinearFunction::PointSlopeForm(0, initial_angles[j], initial_rates[j]));
586  }
587  std::vector<CartesianPoint2d, Eigen::aligned_allocator<CartesianPoint2d> > pseudo_points(dimension());
588  std::vector<LinearFunction> nominal_rate_lines(dimension());
589  WayPoint<JointAngles> pre_pseudo_waypoint(dimension());
590  double t_pullback = 0.001; // start with 1ms
591  double t_pullback_max_ = waypoints[0].duration();
592  double t_pre_intersect_duration = 0.0; // duration from the pulled back wp0 to the intersection point
593  bool acceleration_constraint_broken = true;
594  while (acceleration_constraint_broken && (t_pullback <= t_pullback_max_))
595  {
596  // establish t_pre_intersect_duration as the minimum time to the intersection of initial tangent
597  // and nominal rate line
598  t_pre_intersect_duration = t_pullback_max_ / 2;
599  for (unsigned int j = 0; j < dimension(); ++j)
600  {
601  LinearFunction nominal_rate_line = LinearFunction::PointSlopeForm(
602  t_pullback, initial_angles[j], -1 * ecl::psign(initial_rates[j]) * waypoints[0].nominalRates()[j]);
603  CartesianPoint2d pseudo_point = LinearFunction::Intersection(initial_tangents[j], nominal_rate_line);
604  if (pseudo_point.x() < t_pre_intersect_duration)
605  {
606  t_pre_intersect_duration = pseudo_point.x();
607  }
608  nominal_rate_lines[j] = nominal_rate_line;
609  }
610  acceleration_constraint_broken = false;
611  for (unsigned int j = 0; j < dimension(); ++j)
612  {
613  CartesianPoint2d pseudo_point(t_pre_intersect_duration, initial_tangents[j](t_pre_intersect_duration));
614  // from the pseudo way point to the next way point (wp1)
615  double pseudo_point_duration = t_pullback + waypoints[0].duration() - t_pre_intersect_duration;
616  // Will test 5 positions, which cover all of t_pre_intersect_duration
617  // and half of pseudo_point_duration
618  for (unsigned int i = 1; i <= 5; ++i)
619  {
620  double t_l = t_pre_intersect_duration - i * t_pre_intersect_duration / 5.0;
621  double t_r = t_pre_intersect_duration + i * pseudo_point_duration / 10.0;
622  LinearFunction segment = LinearFunction::Interpolation(pseudo_point.x(), pseudo_point.y(),
623  t_pullback + waypoints[0].duration(),
624  waypoints[1].angles()[j]);
625  double y_0 = initial_tangents[j](t_l);
626  double y_0_dot = initial_tangents[j].derivative(t_l);
627  double y = segment(t_r);
628  double y_dot = segment.derivative(t_r); // slope
629  QuinticPolynomial quintic = QuinticPolynomial::Interpolation(t_l, y_0, y_0_dot, 0.0, t_r, y, y_dot, 0.0);
630  if ((fabs(CubicPolynomial::Maximum(t_l, t_r, quintic.derivative().derivative())) < fabs(max_accelerations[j]))
631  && (fabs(CubicPolynomial::Minimum(t_l, t_r, quintic.derivative().derivative())) < fabs(max_accelerations[j])))
632  {
633  acceleration_constraint_broken = false;
634  break; // we're good, get out and continue through all the joints
635  }
636  if (i == 5)
637  {
638 #ifdef DEBUG_LINEAR_INTERPOLATION
639  std::cout << "Linear Interpolation: pre psuedo point failed with acceleration checks [" << t_pre_intersect_duration << "][" << t_pullback << "]" << std::endl;
640 #endif
641  acceleration_constraint_broken = true;
642  }
643  }
644  }
645  t_pullback = t_pullback * 2; // takes 11 runs to get from 1ms to 1s; adjust, if this is too much
646  }
647  if (acceleration_constraint_broken)
648  {
649  throw DataException<int>(LOC, ConstructorError, "Max acceleration bound broken by pre pseudo point.", 0);
650  }
651  pre_pseudo_waypoint.duration(t_pullback + waypoints[0].duration() - t_pre_intersect_duration);
652  for (unsigned int j = 0; j < dimension(); ++j)
653  {
654  pre_pseudo_waypoint.angles()[j] = initial_tangents[j](t_pre_intersect_duration);
655  }
656 #ifdef DEBUG_LINEAR_INTERPOLATION
657  std::cout << "Linear Interpolation: pre psuedo point done!" << std::endl;
658  std::cout << " : angles " << pre_pseudo_waypoint.angles() << std::endl;
659  std::cout << " : pre pseudo duration " << t_pre_intersect_duration << std::endl;
660  std::cout << " : modified first waypoint duration " << pre_pseudo_waypoint.duration() << std::endl;
661 #endif
662 
663  /******************************************
664  ** Make the post pseudo point.
665  *******************************************/
666  std::vector<double> final_angles, final_rates;
667  for (unsigned int j = 0; j < dimension(); ++j)
668  {
669  final_angles.push_back(waypoints[n].angles()[j]);
670  final_rates.push_back(waypoints[n].rates()[j]);
671  nominal_rate_lines[j] = LinearFunction::PointSlopeForm(
672  0, final_angles[j], -1 * ecl::psign(final_rates[j]) * waypoints[n - 1].nominalRates()[j]);
673  }
674  std::vector<LinearFunction> final_tangents(dimension());
675  WayPoint<JointAngles> post_pseudo_waypoint(dimension());
676  double t_pullforward = 0.001; // start with 1ms
677  double t_pullforward_max_ = waypoints[n - 1].duration();
678  double t_post_intersect_duration = 0.0; // duration from the pulled back wp0 to the intersection point
679  acceleration_constraint_broken = true;
680  while (acceleration_constraint_broken && (t_pullforward <= t_pullforward_max_))
681  {
682  // establish t_final as the maximum time to the intersection of final tangent and nominal rate line
683  t_post_intersect_duration = 0.0;
684  for (unsigned int j = 0; j < dimension(); ++j)
685  {
686  LinearFunction final_tangent = LinearFunction::PointSlopeForm(t_pullforward, final_angles[j], final_rates[j]);
687  final_tangents[j] = final_tangent;
688  CartesianPoint2d pseudo_point = LinearFunction::Intersection(final_tangents[j], nominal_rate_lines[j]);
689  if (pseudo_point.x() > t_post_intersect_duration)
690  {
691  t_post_intersect_duration = pseudo_point.x();
692  }
693  }
694  // check acceleration constraints
695  acceleration_constraint_broken = false;
696  for (unsigned int j = 0; j < dimension(); ++j)
697  {
698  CartesianPoint2d pseudo_point(t_post_intersect_duration, final_tangents[j](t_post_intersect_duration));
699  double pseudo_point_duration = t_pullforward - t_post_intersect_duration;
700  for (unsigned int i = 1; i <= 5; ++i)
701  {
702  double t_l = t_post_intersect_duration - i * (waypoints[n - 1].duration() + t_post_intersect_duration) / 10.0;
703  double t_r = t_post_intersect_duration + i * pseudo_point_duration / 5.0;
704  LinearFunction segment = LinearFunction::Interpolation(-waypoints[n - 1].duration(),
705  waypoints[n - 1].angles()[j], pseudo_point.x(),
706  pseudo_point.y());
707  double y_0 = segment(t_l);
708  double y_0_dot = segment.derivative(t_l);
709  double y = final_tangents[j](t_r);
710  double y_dot = final_tangents[j].derivative(t_r);
711  QuinticPolynomial quintic = QuinticPolynomial::Interpolation(t_l, y_0, y_0_dot, 0.0, t_r, y, y_dot, 0.0);
712  if ((fabs(CubicPolynomial::Maximum(t_l, t_r, quintic.derivative().derivative())) < fabs(max_accelerations[j]))
713  && (fabs(CubicPolynomial::Minimum(t_l, t_r, quintic.derivative().derivative())) < fabs(max_accelerations[j])))
714  {
715  acceleration_constraint_broken = false;
716  break; // we're good, get out and continue through all the joints
717  }
718  if (i == 5)
719  {
720 #ifdef DEBUG_LINEAR_INTERPOLATION
721  std::cout << "Linear Interpolation: post psuedo point failed with acceleration checks [" << t_post_intersect_duration << "][" << t_pullforward << "]" << std::endl;
722 #endif
723  acceleration_constraint_broken = true;
724  }
725  }
726  }
727  t_pullforward = t_pullforward * 2; // takes 12 runs to get from 1ms to 1s, adjust, if this is too much
728  }
729  if (acceleration_constraint_broken)
730  {
731  throw DataException<int>(LOC, ConstructorError, "Max acceleration bound broken by pre pseudo point.", 0);
732  }
733  post_pseudo_waypoint.duration(t_pullforward - t_post_intersect_duration);
734  for (unsigned int j = 0; j < dimension(); ++j)
735  {
736  post_pseudo_waypoint.angles()[j] = final_tangents[j](t_post_intersect_duration);
737  }
738 #ifdef DEBUG_LINEAR_INTERPOLATION
739  std::cout << "Linear Interpolation: post psuedo point done!" << std::endl;
740  std::cout << " : angles " << post_pseudo_waypoint.angles() << std::endl;
741  std::cout << " : modified last point duration " << waypoints[n-1].duration() + t_post_intersect_duration << std::endl;
742  std::cout << " : post pseudo duration " << post_pseudo_waypoint.duration() << std::endl;
743 #endif
744 
745  /*********************
746  ** Waypoint Times
747  **********************/
748  // n+3 points (w_0...w_n + pre and post pseudos)
749  // n+3 waypoint_times
750  waypoint_times[0] = 0.0;
751  waypoint_times[1] = t_pre_intersect_duration;
752  waypoint_times[2] = t_pre_intersect_duration + pre_pseudo_waypoint.duration();
753  for (unsigned int i = 2; i < n; ++i)
754  {
755  waypoint_times[i + 1] = waypoint_times[i] + waypoints[i - 1].duration();
756  }
757  waypoint_times[n + 1] = waypoint_times[n] + waypoints[n - 1].duration() + t_post_intersect_duration;
758  waypoint_times[n + 2] = waypoint_times[n + 1] + post_pseudo_waypoint.duration();
759 
760 #ifdef DEBUG_LINEAR_INTERPOLATION
761  std::cout << "Linear Interpolation: waypoint time estimates before interpolation: " << waypoint_times << std::endl;
762 #endif
763 
764  for (unsigned int j = 0; j < dimension(); ++j)
765  {
766  /******************************************
767  ** Set Values
768  *******************************************/
769  values[0] = waypoints[0].angles()[j];
770  values[1] = pre_pseudo_waypoint.angles()[j];
771  for (unsigned int i = 2; i <= n; ++i)
772  {
773  values[i] = waypoints[i - 1].angles()[j];
774  }
775  values[n + 1] = post_pseudo_waypoint.angles()[j];
776  values[n + 2] = waypoints[n].angles()[j];
777 #ifdef DEBUG_LINEAR_INTERPOLATION
778  std::cout << "Linear Interpolation: values[" << j << "]: " << values << std::endl;
779 #endif
780 
781  /******************************************
782  ** Generate Spline
783  *******************************************/
784  try
785  {
786  splines[j] = SmoothLinearSpline::Interpolation(waypoint_times, values, max_accelerations[j]);
787  }
788  catch (DataException<int> &e)
789  {
790  throw DataException<int>(LOC, e);
791  }
792  }
793 #ifdef DEBUG_LINEAR_INTERPOLATION
794  for ( unsigned int j = 0; j < dimension(); ++j)
795  {
796  std::cout << "Linear Interpolation: discretised domain [" << j << "]: " << splines[j].domain() << std::endl;
797  }
798 #endif
799  return splines;
800 }
801 
802 Array<TensionSpline> Trajectory<JointAngles>::generateTensionSplines(const double& tension, const double initial_time)
803 {
804 
805  Array<TensionSpline> tension_splines(dimension());
806  unsigned int n = waypoints.size() - 1; // n = number of segments
807  // Include all waypoints (even w_0 and w_n). We set up pre and post pseudo points later.
808  Array<double> waypoint_times(n + 1), values(n + 1);
809  waypoint_times[0] = initial_time;
810  for (unsigned int i = 1; i < n + 1; ++i)
811  {
812  waypoint_times[i] = waypoint_times[i - 1] + waypoints[i - 1].duration();
813  }
814 
815  for (unsigned int j = 0; j < dimension(); ++j)
816  {
817  for (unsigned int i = 0; i < n + 1; ++i)
818  {
819  values[i] = waypoints[i].angles()[j];
820  }
821  tension_splines[j] = TensionSpline::Natural(waypoint_times, values, tension);
822  }
823  return tension_splines;
824 }
825 
826 } // namespace ecl
ConstructorError
static blueprints::C2TensionSpline Natural(const Array< double > &x_set, const Array< double > &y_set, const double &tau) ecl_assert_throw_decl(StandardException)
Primary template for waypoints.
Definition: waypoint.hpp:46
#define LOC
#define ecl_assert_throw(expression, exception)
ConfigurationError
OutOfRangeError
Parameter< double > duration
Timestamp for this waypoint.
Definition: waypoint.hpp:376
Array< double > & angles()
Handle to the joint angle array.
Definition: waypoint.hpp:186
const Data & data() const
ecl_geometry_PUBLIC int size(const Trajectory2D &trajectory)
static size_type size()
int psign(const Scalar &x)
static SmoothLinearSpline Interpolation(const Array< double > &x_data, const Array< double > &y_data, double a_max)
reference back()
Primary template for manipulator trajectories.
Definition: trajectory.hpp:57
WayPoint specialisation with joint (motor) angle storage format.
Definition: waypoint.hpp:73
reference front()
ecl_geometry_PUBLIC double distance(const Pose2D &pose, const Trajectory2D &trajectory)
Polynomial< N-1 > derivative() const


ecl_manipulators
Author(s): Daniel Stonier
autogenerated on Mon Jun 10 2019 13:09:10