trajectory.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
33 #include <angles/angles.h>
34 #include <cstdlib>
35 
36 #define MAX_ALLOWABLE_TIME 1.0e8
37 #define EPS_TRAJECTORY 1.0e-8
38 
39 #define MAX_NUM_POINTS 1000
40 #define MAX_COEFF_SIZE 5
41 
42 using namespace trajectory;
43 
44 Trajectory::Trajectory(int dimension): dimension_(dimension)
45 {
46  interp_method_ = "linear";
47  autocalc_timing_ = false;
48  init(MAX_NUM_POINTS,dimension);
49 }
50 
51 void Trajectory::init(int num_points, int dimension)
52 {
53  tp_.resize(num_points,dimension);
54  tc_.resize(num_points-1);
55  min_limit_.resize(dimension);
56  max_limit_.resize(dimension);
57  max_rate_.resize(dimension);
58  max_acc_.resize(dimension);
59  joint_wraps_.resize(dimension);
60  for(int i=0; i<num_points; i++)
61  {
62  tp_[i].setDimension(dimension);
63  }
64 
65  for(int i=0; i<num_points-1; i++)
66  {
67  tc_[i].coeff_.resize(dimension);
68  for(int j=0; j < dimension; j++)
69  tc_[i].coeff_[j].resize(MAX_COEFF_SIZE);
70  }
71  for(int i=0; i < dimension; i++)
72  {
73  joint_wraps_[i] = false;
74  }
75 }
76 
78 {
79  tp_.resize(0);
80  tc_.resize(0);
81  min_limit_.resize(0);
82  max_limit_.resize(0);
83  max_rate_.resize(0);
84  max_acc_.resize(0);
85 }
86 
87 int Trajectory::setTrajectory(const std::vector<TPoint>& tp)
88 {
89  if(tp.size() < 2)
90  {
91  ROS_WARN("Trying to set trajectory with number of points <= 0");
92  return -1;
93  }
94  if(tp.begin()->dimension_ != dimension_)
95  {
96  ROS_WARN("Dimension of trajectory point %d does not match dimension of trajectory %d",tp[0].dimension_, dimension_);
97  return -1;
98  }
99 
100 // ROS_INFO("Initializing trajectory with %d points",tp.size());
101 
102  num_points_ = tp.size();
103 
104 // tp_.resize(num_points_);
105 
106  for(int i=0; i<num_points_; i++)
107  {
108 // tp_[i].setDimension(dimension_);
109  tp_[i] = tp[i];
110 
111  for(int j=0; j<dimension_; j++)
112  {
113  if(joint_wraps_[j])
114  {
115 // ROS_INFO("Wrapping joint angle for joint: %d",j);
116  tp_[i].q_[j] = angles::normalize_angle(tp_[i].q_[j]);
117  }
118  }
119 // ROS_INFO("Input point: %d is ",i);
120 // for(int j=0; j < dimension_; j++)
121 // ROS_INFO("%f ",tp_[i].q_[j]);
122 
123 // ROS_INFO(" ");
124  }
125 
126  parameterize();
127  return 1;
128 }
129 
130 int Trajectory::setTrajectory(const std::vector<double> &p, int numPoints)
131 {
132  num_points_ = numPoints;
133 
134  if((int) p.size() < num_points_*dimension_)
135  {
136  ROS_WARN("Input has only %zd values, expecting %d values for a %d dimensional trajectory with %d number of points",p.size(), num_points_*dimension_, dimension_, num_points_);
137  return -1;
138  }
139  autocalc_timing_ = true;//Enable autocalc timing by default since no time information given in trajectory
140 //tp_.resize(num_points_);
141 
142  for(int i=0; i<num_points_;i++)
143  {
144 // tp_[i].setDimension(dimension_);
145  tp_[i].time_ = 0.0;
146  for(int j=0; j<dimension_; j++)
147  {
148  tp_[i].q_[j] = p[i*dimension_+j];
149  tp_[i].qdot_[j] = 0.0;
150  }
151 
152 // ROS_INFO("Input point: %d is ",i);
153 // for(int j=0; j < dimension_; j++)
154 // ROS_INFO("%f ",tp_[i].q_[j]);
155 
156 // ROS_INFO(" ");
157 
158  }
159  parameterize();
160  return 1;
161 }
162 
164 {
165  if(index > dimension_)
166  {
167  ROS_ERROR("Index exceeds number of joints");
168  return;
169  }
170  joint_wraps_[index] = true;
171 }
172 
173 double Trajectory::jointDiff(double from, double to, int index)
174 {
175  if(joint_wraps_[index])
176  {
177 // ROS_INFO("Returning shortest angular difference from: %f and to: %f",from,to);
178  return angles::shortest_angular_distance(from,to);
179  }
180  else
181  {
182 // ROS_INFO("Returning angular difference from: %f and to: %f",from,to);
183  return (to-from);
184  }
185 }
186 
187 int Trajectory::setTrajectory(const std::vector<double> &p, const std::vector<double> &time, int numPoints)
188 {
189  num_points_ = numPoints;
190 
191 // tp_.resize(num_points_);
192 
193  if((int) time.size() != num_points_)
194  {
195  ROS_WARN("Number of points in vector specifying time (%d) does not match number of points %d",(int) time.size(), num_points_);
196  return -1;
197  }
198  if((int) p.size() < num_points_*dimension_)
199  {
200  ROS_WARN("Input has only %zd values, expecting %d values for a %d dimensional trajectory with %d number of points",p.size(), num_points_*dimension_, dimension_, num_points_);
201  return -1;
202  }
203 
204  for(int i=0; i<num_points_;i++)
205  {
206 // tp_[i].setDimension(dimension_);
207  tp_[i].time_ = time[i];
208  for(int j=0; j<dimension_; j++)
209  {
210  tp_[i].q_[j] = p[i*(dimension_)+j];
211  }
212  }
213 
214  parameterize();
215 
216  return 1;
217 }
218 
219 int Trajectory::setTrajectory(const std::vector<double> &p, const std::vector<double> &pdot, const std::vector<double> &time, int numPoints)
220 {
221  num_points_ = numPoints;
222 
223 // tp_.resize(num_points_);
224 
225  if((int) time.size() != num_points_)
226  {
227  ROS_WARN("Number of points in vector specifying time (%d) does not match number of points %d",(int) time.size(), num_points_);
228  return -1;
229  }
230  if((int) p.size() < num_points_*dimension_)
231  {
232  ROS_WARN("Input has only %zd values, expecting %d values for a %d dimensional trajectory with %d number of points",p.size(), num_points_*dimension_, dimension_, num_points_);
233  return -1;
234  }
235 
236  for(int i=0; i<num_points_;i++)
237  {
238 // tp_[i].setDimension(dimension_);
239  tp_[i].time_ = time[i];
240  for(int j=0; j<dimension_; j++)
241  {
242  tp_[i].q_[j] = p[i*dimension_+j];
243  tp_[i].qdot_[j] = pdot[i*dimension_+j];
244  }
245  }
246  parameterize();
247  return 1;
248 }
249 
251 {
252  double time = tp.time_;
253 
254  int index = findTrajectorySegment(time);
255  std::vector<TPoint>::iterator it = tp_.begin() + index;
256  tp_.insert(it,tp);
257  num_points_++;
258  parameterize();
259 }
260 
262 {
263  int result = 0;
264 
265  while(time > tp_[result+1].time_)
266  result++;
267 
268  return result;
269 }
270 
271 //inline double Trajectory::getTotalTime()
273 {
274  if(num_points_ == 0)
275  return 0.0;
276 
277 // return (tp_.back().time_ - tp_.front().time_);
278  return (lastPoint().time_ - tp_.front().time_);
279 }
280 
281 
283 {
284  return *(tp_.begin()+num_points_-1);
285 }
286 
287 int Trajectory::sample(TPoint &tp, double time)
288 {
289 // ROS_INFO("Trajectory has %d points",num_points_);
290 // ROS_INFO("Time: %f, %f, %f",time,tp_.front().time_,lastPoint().time_);
291  if(time > lastPoint().time_)
292  {
293 // ROS_WARN("Invalid input sample time.");
294  time = lastPoint().time_;
295  }
296  else if( time < tp_.front().time_)
297  {
298  time = tp_.front().time_;
299 // ROS_WARN("Invalid input sample time.");
300  }
301 
302  if((int) tp.q_.size() != dimension_ || (int) tp.qdot_.size() != dimension_)
303  {
304  ROS_WARN("Dimension of sample point passed in = %zd does not match dimension of trajectory = %d",tp.q_.size(),dimension_);
305  return -1;
306  }
307  int segment_index = findTrajectorySegment(time);
308 // ROS_INFO("segment index : %d",segment_index);
309  if(interp_method_ == std::string("linear"))
310  sampleLinear(tp,time,tc_[segment_index],tp_[segment_index].time_);
311  else if(interp_method_ == std::string("cubic"))
312  sampleCubic(tp,time,tc_[segment_index],tp_[segment_index].time_);
313  else if(interp_method_ == std::string("blended_linear"))
314  sampleBlendedLinear(tp,time,tc_[segment_index],tp_[segment_index].time_);
315  else
316  ROS_WARN("Unrecognized interp_method type: %s\n",interp_method_.c_str());
317 
318  return 1;
319 }
320 
321 /*
322 int Trajectory::sample(std::vector<TPoint> &tp, double start_time, double end_time)
323 {
324  if(time > lastPoint().time_ || time < tp_.front().time_)
325  {
326  ROS_WARN("Invalid input sample time.");
327  return -1;
328  }
329  if((int) tp.q_.size() != dimension_ || (int) tp.qdot_.size() != dimension_)
330  {
331  ROS_WARN("Dimension of sample point passed in = %d does not match dimension of trajectory = %d",tp.q_.size(),dimension_);
332  return -1;
333  }
334  int segment_index = findTrajectorySegment(time);
335 
336  if(interp_method_ == std::string("linear"))
337  sampleLinear(tp,time,tc_[segment_index],tp_[segment_index].time_);
338  else if(interp_method_ == std::string("cubic"))
339  sampleCubic(tp,time,tc_[segment_index],tp_[segment_index].time_);
340  else if(interp_method_ == std::string("blended_linear"))
341  sampleBlendedLinear(tp,time,tc_[segment_index],tp_[segment_index].time_);
342  else
343  ROS_WARN("Unrecognized interp_method type: %s\n",interp_method_.c_str());
344 
345  return 1;
346 }
347 */
348 
349 int Trajectory::setMaxRates(std::vector<double> max_rate)
350 {
351  if((int) max_rate.size() != dimension_)
352  {
353  ROS_WARN("Input size: %zd does not match dimension of trajectory = %d",max_rate.size(),dimension_);
354  return -1;
355  }
356 // max_rate.resize(dimension_);
357  for(int i=0; i < dimension_; i++)
358  max_rate_[i] = max_rate[i];
359 
360  max_rate_set_ = true;
361 
362  return 1;
363 }
364 
365 int Trajectory::setMaxAcc(std::vector<double> max_acc)
366 {
367  if((int) max_acc.size() != dimension_)
368  {
369  ROS_WARN("Input size: %zd does not match dimension of trajectory = %d",max_acc.size(),dimension_);
370  return -1;
371  }
372 // max_acc.resize(dimension_);
373  for(int k=0; k < dimension_; k++)
374  max_acc_[k] = max_acc[k];
375 
376  max_acc_set_ = true;
377 
378  return 1;
379 }
380 
382 {
383  int error_code = -1;
384  if(interp_method_ == std::string("linear"))
386  else if(interp_method_ == std::string("cubic"))
388  else if(interp_method_ == std::string("blended_linear"))
390  else
391  ROS_WARN("minimizeSegmentTimes:: Unrecognized interp_method type: %s\n",interp_method_.c_str());
392 
393  return error_code;
394 }
395 
397 {
398  double dT(0);
399 
400 /* TCoeff tc;
401  std::vector<std::vector<double> > coeff;
402  std::vector<double> temp;
403  temp.resize(2);
404  tc.degree_ = 1;
405  tc.dimension_ = dimension_;
406  tc_.clear();
407 */
408 
409  double temp[2];
410 
411  if(!max_rate_set_ || (int) max_rate_.size() < 0)
412  {
413  ROS_WARN("Trying to apply rate limits without setting max rate information. Use setMaxRate first");
414  return -1;
415  }
416 
417  for(int i=1; i < (int) num_points_ ; i++)
418  {
419 // tc.coeff_.clear();
420  dT = calculateMinimumTimeLinear(tp_[i-1],tp_[i]);
421  tp_[i].time_ = tp_[i-1].time_ + dT;
422 
423 // tc.duration_ = dT;
424  tc_[i-1].duration_ = dT;
425 
426  for(int j=0; j < dimension_; j++)
427  {
428  temp[0] = tp_[i-1].q_[j];
429 // temp[1] = (tp_[i].q_[j] - tp_[i-1].q_[j])/tc_[i-1].duration_;
430  temp[1] = jointDiff(tp_[i-1].q_[j],tp_[i].q_[j],j)/tc_[i-1].duration_;
431 
432  tc_[i-1].coeff_[j][0] = temp[0];
433  tc_[i-1].coeff_[j][1] = temp[1];
434  tc_[i-1].degree_ = 1;
435  tc_[i-1].dimension_ = dimension_;
436 
437 // tc.coeff_.push_back(temp);
438  }
439 // tc_.push_back(tc);
440  }
441  return 1;
442 }
443 
445 {
446  double dT(0);
447 
448 /* TCoeff tc;
449  std::vector<double> temp;
450  temp.resize(4);
451  tc.degree_ = 1;
452  tc.dimension_ = dimension_;
453  tc_.clear();
454 */
455 
456  double temp[4];
457 
458  if(!max_rate_set_ || (int) max_rate_.size() < 1)
459  {
460  ROS_WARN("Trying to apply rate limits without setting max rate information. Use setMaxRate first");
461  return -1;
462  }
463 
464  for(int i=1; i < (int) num_points_ ; i++)
465  {
466 // tc.coeff_.clear();
467  dT = calculateMinimumTimeCubic(tp_[i-1],tp_[i]);
468  tp_[i].time_ = tp_[i-1].time_ + dT;
469 // tc.duration_ = dT;
470  tc_[i-1].duration_ = dT;
471 
472  for(int j=0; j < dimension_; j++)
473  {
474  double diff = jointDiff(tp_[i-1].q_[j],tp_[i].q_[j],j);
475  temp[0] = tp_[i-1].q_[j];
476  temp[1] = tp_[i-1].qdot_[j];
477 // temp[2] = (3*(tp_[i].q_[j]-tp_[i-1].q_[j])-(2*tp_[i-1].qdot_[j]+tp_[i].qdot_[j])*tc_[i-1].duration_)/(tc_[i-1].duration_*tc_[i-1].duration_);
478 // temp[3] = (2*(tp_[i-1].q_[j]-tp_[i].q_[j])+(tp_[i-1].qdot_[j]+tp_[i].qdot_[j])*tc_[i-1].duration_)/(pow(tc_[i-1].duration_,3));
479  temp[2] = (3*diff-(2*tp_[i-1].qdot_[j]+tp_[i].qdot_[j])*tc_[i-1].duration_)/(tc_[i-1].duration_*tc_[i-1].duration_);
480  temp[3] = (-2*diff+(tp_[i-1].qdot_[j]+tp_[i].qdot_[j])*tc_[i-1].duration_)/(pow(tc_[i-1].duration_,3));
481 
482  tc_[i-1].coeff_[j][0] = temp[0];
483  tc_[i-1].coeff_[j][1] = temp[1];
484  tc_[i-1].coeff_[j][2] = temp[2];
485  tc_[i-1].coeff_[j][3] = temp[3];
486  tc_[i-1].degree_ = 1;
487  tc_[i-1].dimension_ = dimension_;
488 
489 // tc.coeff_.push_back(temp);
490  }
491 // tc_.push_back(tc);
492  }
493  return 1;
494 }
495 
496 
498 {
499  double dT(0),acc(0.0),tb(0.0);
500 
501 /* TCoeff tc;
502  std::vector<double> temp;
503  temp.resize(5);
504  tc.degree_ = 1;
505  tc.dimension_ = dimension_;
506  tc_.clear();
507 */
508 
509  double temp[5];
510 
511  if(!max_rate_set_ || (int) max_rate_.size() != dimension_ || !max_acc_set_ || (int) max_acc_.size() != dimension_)
512  {
513  ROS_WARN("Trying to apply rate and acc limits without setting them. Use setMaxRate and setMaxAcc first");
514  return -1;
515  }
516 
517  for(int i=1; i < (int) num_points_ ; i++)
518  {
519 // tc.coeff_.clear();
520  dT = calculateMinimumTimeLSPB(tp_[i-1],tp_[i]);
521  tp_[i].time_ = tp_[i-1].time_ + dT;
522 // tc.duration_ = dT;
523  tc_[i-1].duration_ = dT;
524  for(int j=0; j < dimension_; j++)
525  {
526  double diff = jointDiff(tp_[i-1].q_[j],tp_[i].q_[j],j);
527 // if(tp_[i].q_[j]-tp_[i-1].q_[j] > 0)
528  if(diff > 0)
529  acc = max_acc_[j];
530  else
531  acc = -max_acc_[j];
532 // tb = blendTime(acc,-acc*tc_[i-1].duration_,tp_[i].q_[j]-tp_[i-1].q_[j]);
533  tb = blendTime(acc,-acc*tc_[i-1].duration_,diff);
534 
535  temp[0] = tp_[i-1].q_[j];
536  temp[1] = 0;
537  temp[2] = 0.5*acc;
538  temp[3] = tb;
539  temp[4] = std::max(tc_[i-1].duration_-2*tb,0.0);
540 
541  tc_[i-1].coeff_[j][0] = temp[0];
542  tc_[i-1].coeff_[j][1] = temp[1];
543  tc_[i-1].coeff_[j][2] = temp[2];
544  tc_[i-1].coeff_[j][3] = temp[3];
545  tc_[i-1].coeff_[j][4] = temp[4];
546  tc_[i-1].degree_ = 1;
547  tc_[i-1].dimension_ = dimension_;
548 // tc.coeff_.push_back(temp);
549  }
550 // tc_.push_back(tc);
551  }
552  return 1;
553 }
554 
555 double Trajectory::blendTime(double aa,double bb,double cc)
556 {
557  double disc = (pow(bb,2) - 4*aa*cc);
558  if(disc < 0)
559  return 0.0;
560 
561  double tb1 = (-bb + sqrt(disc))/(2*aa);
562  double tb2 = (-bb - sqrt(disc))/(2*aa);
563  if(std::isnan(tb1))
564  tb1 = 0.0;
565  if(std::isnan(tb2))
566  tb2 = 0.0;
567  return std::min(tb1,tb2);
568 }
569 
570 
571 void Trajectory::sampleLinear(TPoint &tp, double time, const TCoeff &tc, double segment_start_time)
572 {
573  double segment_time = time - segment_start_time;
574 // ROS_INFO("Coeff size: %d",tc.coeff_.size());
575 // ROS_INFO("Coeff internal size: %d", tc.coeff_[0].size());
576  for(int i =0; i < dimension_; i++)
577  {
578 // ROS_INFO("Coeffs: %f %f", tc.coeff_[i][0], tc.coeff_[i][1]);
579  tp.q_[i] = tc.coeff_[i][0] + segment_time * tc.coeff_[i][1];
580  tp.qdot_[i] = tc.coeff_[i][1];
581 
582  if(joint_wraps_[i])
583  tp.q_[i] = angles::normalize_angle(tp.q_[i]);
584 
585  }
586  tp.time_ = time;
587  tp.dimension_ = dimension_;
588 }
589 
590 
591 void Trajectory::sampleBlendedLinear(TPoint &tp, double time, const TCoeff &tc, double segment_start_time)
592 {
593  double segment_time = time - segment_start_time;
594  for(int i =0; i < dimension_; i++)
595  {
596  double taccend = tc.coeff_[i][3];
597  double tvelend = tc.coeff_[i][3] + tc.coeff_[i][4];
598  double tvel = tc.coeff_[i][4];
599  double acc = tc.coeff_[i][2]*2;
600  double v0 = tc.coeff_[i][1];
601 
602  if(segment_time <= taccend)
603  {
604  tp.q_[i] = tc.coeff_[i][0] + segment_time * v0 + 0.5 * segment_time * segment_time * acc;
605  tp.qdot_[i] = tc.coeff_[i][1] + segment_time * acc;
606  }
607  else if(segment_time >= tvelend)
608  {
609  double dT = segment_time - tvelend;
610  tp.q_[i] = tc.coeff_[i][0] + v0 * taccend + 0.5 * acc * taccend * taccend + acc * taccend * tvel + acc * taccend * dT - 0.5 * acc * dT * dT;
611  tp.qdot_[i] = acc*taccend - acc*dT;
612  }
613  else
614  {
615  double dT = segment_time - taccend;
616  tp.q_[i] = tc.coeff_[i][0] + v0 * taccend + 0.5 * acc * taccend * taccend + acc * taccend * dT;
617  tp.qdot_[i] = acc * taccend;
618  }
619 
620  if(joint_wraps_[i])
621  tp.q_[i] = angles::normalize_angle(tp.q_[i]);
622  }
623  tp.time_ = time;
624  tp.dimension_ = dimension_;
625 }
626 
627 
628 void Trajectory::sampleCubic(TPoint &tp, double time, const TCoeff &tc, double segment_start_time)
629 {
630  double segment_time = time - segment_start_time;
631  for(int i =0; i < dimension_; i++)
632  {
633  tp.q_[i] = tc.coeff_[i][0] + segment_time * tc.coeff_[i][1] + segment_time*segment_time*tc.coeff_[i][2] + segment_time*segment_time*segment_time*tc.coeff_[i][3];
634  tp.qdot_[i] = tc.coeff_[i][1] + 2*segment_time*tc.coeff_[i][2] + 3*segment_time*segment_time*tc.coeff_[i][3];
635 
636  if(joint_wraps_[i])
637  tp.q_[i] = angles::normalize_angle(tp.q_[i]);
638 
639  }
640  tp.time_ = time;
641  tp.dimension_ = dimension_;
642 }
643 
645 {
646  return num_points_;
647 }
648 
649 int Trajectory::getDuration(std::vector<double> &duration)
650 {
651  if((int) duration.size() != num_points_-1)
652  {
653  ROS_WARN("Size of duration vector %zd does not match number of segments in trajectory %d", duration.size(), num_points_-1);
654  return -1;
655  }
656  for(int i = 0; i < num_points_-1; i++)
657  duration[i] = tc_[i].duration_;
658 
659  return 1;
660 }
661 
662 int Trajectory::getDuration(int index, double &duration)
663 {
664  if(index > num_points_ -1)
665  {
666  ROS_WARN("Index %d outside number of segments in the trajectory %d", index, num_points_-1);
667  return -1;
668  }
669 
670  duration = tc_[index].duration_;
671 
672  return 1;
673 
674 }
675 
676 int Trajectory::getTimeStamps(std::vector<double> &timestamps)
677 {
678  if((int) timestamps.size() != num_points_)
679  {
680  ROS_WARN("Size of timestamps vector %zd does not match number of points in trajectory %d", timestamps.size(), num_points_);
681  return -1;
682  }
683  for(int i = 0; i < num_points_; i++)
684  timestamps[i] = tp_[i].time_;
685 
686  return 1;
687 }
688 
689 double Trajectory::calculateMinimumTimeLinear(const TPoint &start, const TPoint &end)
690 {
691  double minJointTime(MAX_ALLOWABLE_TIME);
692  double minTime(0);
693 
694  for(int i = 0; i < start.dimension_; i++)
695  {
696  double diff = jointDiff(start.q_[i],end.q_[i],i);
697  if(max_rate_[i] > 0)
698 // minJointTime = fabs(end.q_[i]-start.q_[i]) / max_rate_[i];
699  minJointTime = fabs(diff) / max_rate_[i];
700  else
701  minJointTime = MAX_ALLOWABLE_TIME;
702 
703  if(minTime < minJointTime)
704  minTime = minJointTime;
705 
706  }
707 
708  return minTime;
709 }
710 
711 double Trajectory::calculateMinimumTimeCubic(const TPoint &start, const TPoint &end)
712 {
713  double minJointTime(MAX_ALLOWABLE_TIME);
714  double minTime(0);
715 
716  for(int i = 0; i < start.dimension_; i++)
717  {
718  if(max_rate_[i] > 0)
719  minJointTime = calculateMinTimeCubic(start.q_[i],end.q_[i],start.qdot_[i],end.qdot_[i],max_rate_[i],i);
720  else
721  minJointTime = MAX_ALLOWABLE_TIME;
722 
723 // ROS_INFO("Min time: %f",minJointTime);
724 
725  if(minTime < minJointTime)
726  minTime = minJointTime;
727 
728  }
729  return minTime;
730 }
731 
732 double Trajectory::calculateMinTimeCubic(double q0, double q1, double v0, double v1, double vmax, int index)
733 {
735 // double dq = q1 - q0;
736  double dq = jointDiff(q0,q1,index);
737 
738  double v(0.0);
739  if(dq > 0)
740  v = vmax;
741  else
742  v = -vmax;
743 
744  double a = 3.0*(v0+v1)*v - 3.0* (v0+v1)*v0 + pow((2.0*v0+v1),2.0);
745  double b = -6.0*dq*v + 6.0 * v0 *dq - 6.0*dq*(2.0*v0+v1);
746  double c = 9.0 * pow(dq,2);
747 
748  if (fabs(a) > EPS_TRAJECTORY)
749  {
750  if((pow(b,2)-4.0*a*c) >= 0)
751  {
752  t1 = (-b + sqrt(pow(b,2)-4.0*a*c))/(2.0*a);
753  t2 = (-b - sqrt(pow(b,2)-4.0*a*c))/(2.0*a);
754  }
755  }
756  else
757  {
758  t1 = -c/b;
759  t2 = t1;
760  }
761 
762  if(t1 < 0)
763  t1 = MAX_ALLOWABLE_TIME;
764 
765  if(t2 < 0)
766  t2 = MAX_ALLOWABLE_TIME;
767 
768  result = std::min(t1,t2);
769  return result;
770 }
771 
772 double Trajectory::calculateMinimumTimeLSPB(const TPoint &start, const TPoint &end)
773 {
774  double minJointTime(MAX_ALLOWABLE_TIME);
775  double minTime(0);
776 
777  for(int i = 0; i < start.dimension_; i++)
778  {
779  if(max_rate_[i] > 0)
780  minJointTime = calculateMinTimeLSPB(start.q_[i],end.q_[i],max_rate_[i],max_acc_[i],i);
781  else
782  minJointTime = MAX_ALLOWABLE_TIME;
783 
784  if(minTime < minJointTime)
785  minTime = minJointTime;
786 
787  }
788 
789  return minTime;
790 }
791 
792 double Trajectory::calculateMinTimeLSPB(double q0, double q1, double vmax, double amax, int index)
793 {
794  double diff = jointDiff(q0,q1,index);
795 
796  double tb = std::min(fabs(vmax/amax),sqrt(fabs(diff)/amax));
797  double acc(0);
798  if(diff>0)
799  acc = amax;
800  else
801  acc = -amax;
802  double dist_tb = acc*tb*tb;
803  double ts = (diff - dist_tb)/(acc*tb);
804  if(ts < 0)
805  ts = 0;
806  return (2*tb+ts);
807 }
808 
809 
810 void Trajectory::setInterpolationMethod(std::string interp_method)
811 {
812  interp_method_ = interp_method;
813  ROS_INFO("Trajectory:: interpolation type %s",interp_method_.c_str());
814 }
815 
817 {
818  int error_code = -1;
819  if(interp_method_ == std::string("linear"))
820  error_code = parameterizeLinear();
821  else if(interp_method_ == std::string("cubic"))
822  error_code = parameterizeCubic();
823  else if(interp_method_ == std::string("blended_linear"))
824  error_code = parameterizeBlendedLinear();
825  else
826  {
827  ROS_WARN("Unrecognized interp_method type: %s\n",interp_method_.c_str());
828  }
829  return error_code;
830 }
831 
832 
834 {
835  double dT(0);
836 
837 /* TCoeff tc;
838  std::vector<double> temp;
839  temp.resize(2);
840  tc.degree_ = 1;
841  tc.dimension_ = dimension_;
842  tc_.clear();
843 */
844  double temp[2];
845 
846  if(autocalc_timing_)
847  {
848  if(!max_rate_set_ || (int) max_rate_.size() < 0)
849  {
850  ROS_WARN("Trying to apply rate limits without setting max rate information. Use setMaxRate first.");
851  return -1;
852  }
853  }
854  for(int i=1; i < (int) num_points_ ; i++)
855  {
856 // tc.coeff_.clear();
857  dT = tp_[i].time_ - tp_[i-1].time_;
858  if(autocalc_timing_)
859  {
860  double dTMin = calculateMinimumTimeLinear(tp_[i-1],tp_[i]);
861  if(dTMin > dT) // if minimum time required to satisfy limits is greater than time available, stretch this segment
862  dT = dTMin;
863  }
864 
865 // tc.duration_ = dT;
866  tc_[i-1].duration_ = dT;
867 
868  for(int j=0; j < dimension_; j++)
869  {
870  temp[0] = tp_[i-1].q_[j];
871  temp[1] = jointDiff(tp_[i-1].q_[j],tp_[i].q_[j],j)/tc_[i-1].duration_;
872  if(std::isnan(temp[1]))
873  {
874  temp[1] = 0.0;
875 // ROS_WARN("Zero duration between two trajectory points");
876  }
877 // tc.coeff_.push_back(temp);
878  tc_[i-1].coeff_[j][0] = temp[0];
879  tc_[i-1].coeff_[j][1] = temp[1];
880  tc_[i-1].degree_ = 1;
881  tc_[i-1].dimension_ = dimension_;
882  }
883 // tc_.push_back(tc);
884  }
885 
886 /* for(int i=0; i<tc_.size(); i++)
887  {
888  for(int j=0; j<dimension_; j++)
889  ROS_INFO("stored coeff: %d %d %f %f",i,j,tc_[i].coeff_[j][0],tc_[i].coeff_[j][1]);
890  }
891 */
892  // Now modify all the times to bring them up to date
893  for(int i=1; i < (int) num_points_; i++)
894  {
895  tp_[i].time_ = tp_[i-1].time_ + tc_[i-1].duration_;
896 // ROS_INFO("Times: %d %f",i,tp_[i].time_);
897  }
898  return 1;
899 }
900 
901 
902 
904 {
905  double dT(0);
906 
907 /* TCoeff tc;
908  std::vector<double> temp;
909  temp.resize(4);
910  tc.degree_ = 1;
911  tc.dimension_ = dimension_;
912  tc_.clear();
913 */
914 
915  double temp[4];
916 
917  if(autocalc_timing_)
918  {
919  if(!max_rate_set_ || (int) max_rate_.size() < 0)
920  {
921  ROS_WARN("Trying to apply rate limits without setting max rate information. Use setMaxRate first.");
922  return -1;
923  }
924  }
925 
926  for(int i=1; i < (int) num_points_ ; i++)
927  {
928 // tc.coeff_.clear();
929  dT = tp_[i].time_ - tp_[i-1].time_;
930  if(autocalc_timing_)
931  {
932  double dTMin = calculateMinimumTimeCubic(tp_[i-1],tp_[i]);
933  if(dTMin > dT) // if minimum time required to satisfy limits is greater than time available, stretch this segment
934  dT = dTMin;
935  }
936 
937 // tc.duration_ = dT;
938  tc_[i-1].duration_ = dT;
939 
940  for(int j=0; j < dimension_; j++)
941  {
942  double diff = jointDiff(tp_[i-1].q_[j],tp_[i].q_[j],j);
943  temp[0] = tp_[i-1].q_[j];
944  temp[1] = tp_[i-1].qdot_[j];
945  temp[2] = (3*diff-(2*tp_[i-1].qdot_[j]+tp_[i].qdot_[j])*tc_[i-1].duration_)/(tc_[i-1].duration_*tc_[i-1].duration_);
946  temp[3] = (-2*diff+(tp_[i-1].qdot_[j]+tp_[i].qdot_[j])*tc_[i-1].duration_)/(pow(tc_[i-1].duration_,3));
947  if(std::isnan(temp[2]))
948  temp[2] = 0.0;
949  if(std::isnan(temp[3]))
950  temp[3] = 0.0;
951 
952  tc_[i-1].coeff_[j][0] = temp[0];
953  tc_[i-1].coeff_[j][1] = temp[1];
954  tc_[i-1].coeff_[j][2] = temp[2];
955  tc_[i-1].coeff_[j][3] = temp[3];
956  tc_[i-1].degree_ = 1;
957  tc_[i-1].dimension_ = dimension_;
958 
959 // tc.coeff_.push_back(temp);
960  }
961 // tc_.push_back(tc);
962  }
963 
964  // Now modify all the times to bring them up to date
965  for(int i=1; i < (int) num_points_; i++)
966  tp_[i].time_ = tp_[i-1].time_ + tc_[i-1].duration_;
967 
968  return 1;
969 }
970 
971 
973 {
974  double dT(0.0),acc(0.0),tb(0.0);
975 /*
976  TCoeff tc;
977  std::vector<double> temp;
978  temp.resize(5);
979  tc.degree_ = 1;
980  tc.dimension_ = dimension_;
981  tc_.clear();
982 */
983  double temp[5];
984 
985  if(autocalc_timing_)
986  {
987  if(!max_rate_set_ || (int) max_rate_.size() != dimension_ || !max_acc_set_ || (int) max_acc_.size() != dimension_)
988  {
989  ROS_WARN("Trying to apply rate and acc limits without setting max rate or acc information. Use setMaxRate and setMaxAcc first.");
990  return -1;
991  }
992  }
993 
994  for(int i=1; i < (int) num_points_ ; i++)
995  {
996 // tc.coeff_.clear();
997  dT = tp_[i].time_ - tp_[i-1].time_;
998  if(autocalc_timing_)
999  {
1000  double dTMin = calculateMinimumTimeLSPB(tp_[i-1],tp_[i]);
1001  if(dTMin > dT)
1002  dT = dTMin;
1003  }
1004 
1005 // tc.duration_ = dT;
1006  tc_[i-1].duration_ = dT;
1007 
1008  for(int j=0; j < dimension_; j++)
1009  {
1010  double diff = jointDiff(tp_[i-1].q_[j],tp_[i].q_[j],j);
1011  if(diff > 0)
1012  acc = max_acc_[j];
1013  else
1014  acc = -max_acc_[j];
1015 
1016  tb = blendTime(acc,-acc*tc_[i-1].duration_,diff);
1017 
1018  temp[0] = tp_[i-1].q_[j];
1019  temp[1] = 0;
1020  temp[2] = 0.5*acc;
1021  temp[3] = tb;
1022  temp[4] = std::max(tc_[i-1].duration_-2*tb,0.0);
1023 
1024  tc_[i-1].coeff_[j][0] = temp[0];
1025  tc_[i-1].coeff_[j][1] = temp[1];
1026  tc_[i-1].coeff_[j][2] = temp[2];
1027  tc_[i-1].coeff_[j][3] = temp[3];
1028  tc_[i-1].coeff_[j][4] = temp[4];
1029  tc_[i-1].degree_ = 1;
1030  tc_[i-1].dimension_ = dimension_;
1031 
1032 
1033  //ROS_DEBUG("coeff: %d %d %f %f %f %f %f %f\n", i,j,tc.duration_,temp[0],temp[1],temp[2],temp[3],temp[4]);
1034  // tc.coeff_.push_back(temp);
1035  }
1036 // tc_.push_back(tc);
1037  }
1038 
1039  // Now modify all the times to bring them up to date
1040  for(int i=1; i < (int) num_points_; i++)
1041  tp_[i].time_ = tp_[i-1].time_ + tc_[i-1].duration_;
1042 
1043  return 1;
1044 }
1045 
1046 int Trajectory::write(std::string filename, double dT)
1047 {
1048  FILE *f = fopen(filename.c_str(),"w");
1049  double time = tp_.front().time_;
1050  TPoint tp;
1052 
1053  while(time < lastPoint().time_)
1054  {
1055  sample(tp,time);
1056  fprintf(f,"%f ",time);
1057  for(int j=0; j < dimension_; j++)
1058  {
1059  fprintf(f,"%f ",tp.q_[j]);
1060  }
1061  for(int j=0; j < dimension_; j++)
1062  {
1063  fprintf(f,"%f ",tp.qdot_[j]);
1064  }
1065  fprintf(f,"\n");
1066  time += dT;
1067 // printf("%f \n",time);
1068  }
1069  fclose(f);
1070  return 1;
1071 }
1072 
1073 void Trajectory::getTrajectory(std::vector<trajectory::Trajectory::TPoint> &traj, double dT)
1074 {
1075  double time = tp_.front().time_;
1076  TPoint tp;
1078  while(time < lastPoint().time_)
1079  {
1080  sample(tp,time);
1081  traj.push_back(tp);
1082  time += dT;
1083  }
1084 }
void clear()
clear the trajectory
Definition: trajectory.cpp:77
double calculateMinimumTimeLSPB(const TPoint &start, const TPoint &end)
calculate minimum time for a trajectory segment using LSPB.
Definition: trajectory.cpp:772
int parameterizeBlendedLinear()
calculate the coefficients for interpolation between trajectory points using blended linear interpola...
Definition: trajectory.cpp:972
std::vector< bool > joint_wraps_
Definition: trajectory.h:261
std::vector< double > max_rate_
Definition: trajectory.h:257
double calculateMinTimeLSPB(double q0, double q1, double vmax, double amax, int index)
Definition: trajectory.cpp:792
int minimizeSegmentTimes()
Minimize segment times in the trajectory Timings for the trajectory segments are automatically calcul...
Definition: trajectory.cpp:381
f
#define MAX_NUM_POINTS
Definition: trajectory.cpp:39
int parameterize()
calculate the coefficients for interpolation between trajectory points If autocalc_timing_ is true...
Definition: trajectory.cpp:816
void sampleCubic(TPoint &tp, double time, const TCoeff &tc, double segment_start_time)
Sample the trajectory based on a cubic interpolation.
Definition: trajectory.cpp:628
double getTotalTime()
Get the total time for the trajectory.
Definition: trajectory.cpp:272
std::vector< double > q_
Definition: trajectory.h:72
void sampleBlendedLinear(TPoint &tp, double time, const TCoeff &tc, double segment_start_time)
Sample the trajectory based on a cubic interpolation.
Definition: trajectory.cpp:591
double calculateMinimumTimeLinear(const TPoint &start, const TPoint &end)
calculate minimum time for a trajectory segment using a linear interpolation
Definition: trajectory.cpp:689
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
int parameterizeCubic()
calculate the coefficients for interpolation between trajectory points using cubic interpolation...
Definition: trajectory.cpp:903
int minimizeSegmentTimesWithCubicInterpolation()
calculate a minimum time trajectory using cubic interpolation Timings for the trajectory are automati...
Definition: trajectory.cpp:444
int getDuration(std::vector< double > &duration)
Definition: trajectory.cpp:649
int parameterizeLinear()
calculate the coefficients for interpolation between trajectory points using linear interpolation If ...
Definition: trajectory.cpp:833
double calculateMinimumTimeCubic(const TPoint &start, const TPoint &end)
Definition: trajectory.cpp:711
int write(std::string filename, double dT)
#define ROS_WARN(...)
void sampleLinear(TPoint &tp, double time, const TCoeff &tc, double segment_start_time)
Sample the trajectory based on a linear interpolation.
Definition: trajectory.cpp:571
void addPoint(const TPoint)
Add a point to the trajectory.
Definition: trajectory.cpp:250
Trajectory(int dimension)
Constructor for instantiation of the class by specifying the dimension.
Definition: trajectory.cpp:44
double blendTime(double aa, double bb, double cc)
Definition: trajectory.cpp:555
std::vector< std::vector< double > > coeff_
Definition: trajectory.h:112
void init(int num_points, int dimension)
Definition: trajectory.cpp:51
std::vector< TCoeff > tc_
Definition: trajectory.h:251
int minimizeSegmentTimesWithLinearInterpolation()
calculate a minimum time trajectory using linear interpolation Timings for the trajectory are automat...
Definition: trajectory.cpp:396
#define ROS_INFO(...)
#define EPS_TRAJECTORY
Definition: trajectory.cpp:37
double calculateMinTimeCubic(double q0, double q1, double v0, double v1, double vmax, int index)
Definition: trajectory.cpp:732
void setDimension(int dimension)
Set the dimension of a trajectory point. This resizes the internal vectors to the right sizes...
Definition: trajectory.h:86
int getNumberPoints()
Get the number of points in the trajectory.
Definition: trajectory.cpp:644
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
def normalize_angle(angle)
void setJointWraps(int index)
Definition: trajectory.cpp:163
double jointDiff(double from, double to, int index)
Definition: trajectory.cpp:173
std::vector< double > max_limit_
Definition: trajectory.h:253
std::vector< double > min_limit_
Definition: trajectory.h:255
#define MAX_ALLOWABLE_TIME
Definition: trajectory.cpp:36
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
int getTimeStamps(std::vector< double > &timestamps)
Definition: trajectory.cpp:676
std::vector< double > max_acc_
Definition: trajectory.h:259
#define MAX_COEFF_SIZE
Definition: trajectory.cpp:40
const TPoint & lastPoint()
Definition: trajectory.cpp:282
int sample(TPoint &tp, double time)
Sample the trajectory at a certain point in time.
Definition: trajectory.cpp:287
int findTrajectorySegment(double time)
finds the trajectory segment corresponding to a particular time
Definition: trajectory.cpp:261
std::string interp_method_
Definition: trajectory.h:233
void getTrajectory(std::vector< trajectory::Trajectory::TPoint > &traj, double dT)
std::vector< double > qdot_
Definition: trajectory.h:74
std::vector< TPoint > tp_
Definition: trajectory.h:249
#define ROS_ERROR(...)
int setMaxAcc(std::vector< double > max_acc)
Definition: trajectory.cpp:365
void setInterpolationMethod(std::string interp_method)
Set the interpolation method.
Definition: trajectory.cpp:810
int minimizeSegmentTimesWithBlendedLinearInterpolation()
calculate a minimum time trajectory using blended linear interpolation Timings for the trajectory are...
Definition: trajectory.cpp:497
def shortest_angular_distance(from_angle, to_angle)
int setMaxRates(std::vector< double > max_rate)
set the max rates (velocities)
Definition: trajectory.cpp:349
int setTrajectory(const std::vector< TPoint > &tp)
Set the trajectory using a vector of trajectory points.
Definition: trajectory.cpp:87


pr2_mechanism_controllers
Author(s): Sachin Chita, John Hsu, Melonee Wise
autogenerated on Wed Jun 5 2019 19:34:08