timed_elastic_band.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the institute nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Author: Christoph Rösmann
37  *********************************************************************/
38 
40 
41 
42 namespace teb_local_planner
43 {
44 
45 
47 {
48 }
49 
51 {
52  ROS_DEBUG("Destructor Timed_Elastic_Band...");
54 }
55 
56 
57 void TimedElasticBand::addPose(const PoseSE2& pose, bool fixed)
58 {
59  VertexPose* pose_vertex = new VertexPose(pose, fixed);
60  pose_vec_.push_back( pose_vertex );
61  return;
62 }
63 
64 void TimedElasticBand::addPose(const Eigen::Ref<const Eigen::Vector2d>& position, double theta, bool fixed)
65 {
66  VertexPose* pose_vertex = new VertexPose(position, theta, fixed);
67  pose_vec_.push_back( pose_vertex );
68  return;
69 }
70 
71  void TimedElasticBand::addPose(double x, double y, double theta, bool fixed)
72 {
73  VertexPose* pose_vertex = new VertexPose(x, y, theta, fixed);
74  pose_vec_.push_back( pose_vertex );
75  return;
76 }
77 
78 void TimedElasticBand::addTimeDiff(double dt, bool fixed)
79 {
80  VertexTimeDiff* timediff_vertex = new VertexTimeDiff(dt, fixed);
81  timediff_vec_.push_back( timediff_vertex );
82  return;
83 }
84 
85 
86 void TimedElasticBand::addPoseAndTimeDiff(double x, double y, double angle, double dt)
87 {
88  if (sizePoses() != sizeTimeDiffs())
89  {
90  addPose(x,y,angle,false);
91  addTimeDiff(dt,false);
92  }
93  else
94  ROS_ERROR("Method addPoseAndTimeDiff: Add one single Pose first. Timediff describes the time difference between last conf and given conf");
95  return;
96 }
97 
98 
99 
100 void TimedElasticBand::addPoseAndTimeDiff(const PoseSE2& pose, double dt)
101 {
102  if (sizePoses() != sizeTimeDiffs())
103  {
104  addPose(pose,false);
105  addTimeDiff(dt,false);
106  } else
107  ROS_ERROR("Method addPoseAndTimeDiff: Add one single Pose first. Timediff describes the time difference between last conf and given conf");
108  return;
109 }
110 
111 void TimedElasticBand::addPoseAndTimeDiff(const Eigen::Ref<const Eigen::Vector2d>& position, double theta, double dt)
112 {
113  if (sizePoses() != sizeTimeDiffs())
114  {
115  addPose(position, theta,false);
116  addTimeDiff(dt,false);
117  } else
118  ROS_ERROR("Method addPoseAndTimeDiff: Add one single Pose first. Timediff describes the time difference between last conf and given conf");
119  return;
120 }
121 
122 
124 {
125  ROS_ASSERT(index<pose_vec_.size());
126  delete pose_vec_.at(index);
127  pose_vec_.erase(pose_vec_.begin()+index);
128 }
129 
130 void TimedElasticBand::deletePoses(int index, int number)
131 {
132  ROS_ASSERT(index+number<=(int)pose_vec_.size());
133  for (int i = index; i<index+number; ++i)
134  delete pose_vec_.at(i);
135  pose_vec_.erase(pose_vec_.begin()+index, pose_vec_.begin()+index+number);
136 }
137 
139 {
140  ROS_ASSERT(index<(int)timediff_vec_.size());
141  delete timediff_vec_.at(index);
142  timediff_vec_.erase(timediff_vec_.begin()+index);
143 }
144 
145 void TimedElasticBand::deleteTimeDiffs(int index, int number)
146 {
147  ROS_ASSERT(index+number<=timediff_vec_.size());
148  for (int i = index; i<index+number; ++i)
149  delete timediff_vec_.at(i);
150  timediff_vec_.erase(timediff_vec_.begin()+index, timediff_vec_.begin()+index+number);
151 }
152 
153 void TimedElasticBand::insertPose(int index, const PoseSE2& pose)
154 {
155  VertexPose* pose_vertex = new VertexPose(pose);
156  pose_vec_.insert(pose_vec_.begin()+index, pose_vertex);
157 }
158 
159 void TimedElasticBand::insertPose(int index, const Eigen::Ref<const Eigen::Vector2d>& position, double theta)
160 {
161  VertexPose* pose_vertex = new VertexPose(position, theta);
162  pose_vec_.insert(pose_vec_.begin()+index, pose_vertex);
163 }
164 
165 void TimedElasticBand::insertPose(int index, double x, double y, double theta)
166 {
167  VertexPose* pose_vertex = new VertexPose(x, y, theta);
168  pose_vec_.insert(pose_vec_.begin()+index, pose_vertex);
169 }
170 
171 void TimedElasticBand::insertTimeDiff(int index, double dt)
172 {
173  VertexTimeDiff* timediff_vertex = new VertexTimeDiff(dt);
174  timediff_vec_.insert(timediff_vec_.begin()+index, timediff_vertex);
175 }
176 
177 
179 {
180  for (PoseSequence::iterator pose_it = pose_vec_.begin(); pose_it != pose_vec_.end(); ++pose_it)
181  delete *pose_it;
182  pose_vec_.clear();
183 
184  for (TimeDiffSequence::iterator dt_it = timediff_vec_.begin(); dt_it != timediff_vec_.end(); ++dt_it)
185  delete *dt_it;
186  timediff_vec_.clear();
187 }
188 
189 
190 void TimedElasticBand::setPoseVertexFixed(int index, bool status)
191 {
192  ROS_ASSERT(index<sizePoses());
193  pose_vec_.at(index)->setFixed(status);
194 }
195 
196 void TimedElasticBand::setTimeDiffVertexFixed(int index, bool status)
197 {
198  ROS_ASSERT(index<sizeTimeDiffs());
199  timediff_vec_.at(index)->setFixed(status);
200 }
201 
202 
203 void TimedElasticBand::autoResize(double dt_ref, double dt_hysteresis, int min_samples, int max_samples, bool fast_mode)
204 {
205  ROS_ASSERT(sizeTimeDiffs() == 0 || sizeTimeDiffs() + 1 == sizePoses());
207  bool modified = true;
208 
209  for (int rep = 0; rep < 100 && modified; ++rep) // actually it should be while(), but we want to make sure to not get stuck in some oscillation, hence max 100 repitions.
210  {
211  modified = false;
212 
213  for(int i=0; i < sizeTimeDiffs(); ++i) // TimeDiff connects Point(i) with Point(i+1)
214  {
215  if(TimeDiff(i) > dt_ref + dt_hysteresis && sizeTimeDiffs()<max_samples)
216  {
217  //ROS_DEBUG("teb_local_planner: autoResize() inserting new bandpoint i=%u, #TimeDiffs=%lu",i,sizeTimeDiffs());
218 
219  double newtime = 0.5*TimeDiff(i);
220 
221  TimeDiff(i) = newtime;
222  insertPose(i+1, PoseSE2::average(Pose(i),Pose(i+1)) );
223  insertTimeDiff(i+1,newtime);
224 
225  modified = true;
226  }
227  else if(TimeDiff(i) < dt_ref - dt_hysteresis && sizeTimeDiffs()>min_samples) // only remove samples if size is larger than min_samples.
228  {
229  //ROS_DEBUG("teb_local_planner: autoResize() deleting bandpoint i=%u, #TimeDiffs=%lu",i,sizeTimeDiffs());
230 
231  if(i < ((int)sizeTimeDiffs()-1))
232  {
233  TimeDiff(i+1) = TimeDiff(i+1) + TimeDiff(i);
234  deleteTimeDiff(i);
235  deletePose(i+1);
236  }
237  else
238  { // last motion should be adjusted, shift time to the interval before
239  TimeDiff(i-1) += TimeDiff(i);
240  deleteTimeDiff(i);
241  deletePose(i);
242  }
243 
244  modified = true;
245  }
246  }
247  if (fast_mode) break;
248  }
249 }
250 
251 
253 {
254  double time = 0;
255 
256  for(TimeDiffSequence::const_iterator dt_it = timediff_vec_.begin(); dt_it != timediff_vec_.end(); ++dt_it)
257  {
258  time += (*dt_it)->dt();
259  }
260  return time;
261 }
262 
264 {
265  ROS_ASSERT(index<=timediff_vec_.size());
266 
267  double time = 0;
268 
269  for(int i = 0; i < index; ++i)
270  {
271  time += timediff_vec_.at(i)->dt();
272  }
273 
274  return time;
275 }
276 
278 {
279  double dist = 0;
280 
281  for(int i=1; i<sizePoses(); ++i)
282  {
283  dist += (Pose(i).position() - Pose(i-1).position()).norm();
284  }
285  return dist;
286 }
287 
288 bool TimedElasticBand::initTrajectoryToGoal(const PoseSE2& start, const PoseSE2& goal, double diststep, double max_vel_x, int min_samples, bool guess_backwards_motion)
289 {
290  if (!isInit())
291  {
292  addPose(start); // add starting point
293  setPoseVertexFixed(0,true); // StartConf is a fixed constraint during optimization
294 
295  double timestep = 0.1;
296 
297  if (diststep!=0)
298  {
299  Eigen::Vector2d point_to_goal = goal.position()-start.position();
300  double dir_to_goal = std::atan2(point_to_goal[1],point_to_goal[0]); // direction to goal
301  double dx = diststep*std::cos(dir_to_goal);
302  double dy = diststep*std::sin(dir_to_goal);
303  double orient_init = dir_to_goal;
304  // check if the goal is behind the start pose (w.r.t. start orientation)
305  if (guess_backwards_motion && point_to_goal.dot(start.orientationUnitVec()) < 0)
306  orient_init = g2o::normalize_theta(orient_init+M_PI);
307  // TODO: timestep ~ max_vel_x_backwards for backwards motions
308 
309  double dist_to_goal = point_to_goal.norm();
310  double no_steps_d = dist_to_goal/std::abs(diststep); // ignore negative values
311  unsigned int no_steps = (unsigned int) std::floor(no_steps_d);
312 
313  if (max_vel_x > 0) timestep = diststep / max_vel_x;
314 
315  for (unsigned int i=1; i<=no_steps; i++) // start with 1! starting point had index 0
316  {
317  if (i==no_steps && no_steps_d==(float) no_steps)
318  break; // if last conf (depending on stepsize) is equal to goal conf -> leave loop
319  addPoseAndTimeDiff(start.x()+i*dx,start.y()+i*dy,orient_init,timestep);
320  }
321 
322  }
323 
324  // if number of samples is not larger than min_samples, insert manually
325  if ( sizePoses() < min_samples-1 )
326  {
327  ROS_DEBUG("initTEBtoGoal(): number of generated samples is less than specified by min_samples. Forcing the insertion of more samples...");
328  while (sizePoses() < min_samples-1) // subtract goal point that will be added later
329  {
330  // simple strategy: interpolate between the current pose and the goal
331  PoseSE2 intermediate_pose = PoseSE2::average(BackPose(), goal);
332  if (max_vel_x > 0) timestep = (intermediate_pose.position()-BackPose().position()).norm()/max_vel_x;
333  addPoseAndTimeDiff( intermediate_pose, timestep ); // let the optimier correct the timestep (TODO: better initialization
334  }
335  }
336 
337  // add goal
338  if (max_vel_x > 0) timestep = (goal.position()-BackPose().position()).norm()/max_vel_x;
339  addPoseAndTimeDiff(goal,timestep); // add goal point
340  setPoseVertexFixed(sizePoses()-1,true); // GoalConf is a fixed constraint during optimization
341  }
342  else // size!=0
343  {
344  ROS_WARN("Cannot init TEB between given configuration and goal, because TEB vectors are not empty or TEB is already initialized (call this function before adding states yourself)!");
345  ROS_WARN("Number of TEB configurations: %d, Number of TEB timediffs: %d",(unsigned int) sizePoses(),(unsigned int) sizeTimeDiffs());
346  return false;
347  }
348  return true;
349 }
350 
351 
352 bool TimedElasticBand::initTrajectoryToGoal(const std::vector<geometry_msgs::PoseStamped>& plan, double max_vel_x, bool estimate_orient, int min_samples, bool guess_backwards_motion)
353 {
354 
355  if (!isInit())
356  {
357  PoseSE2 start(plan.front().pose);
358  PoseSE2 goal(plan.back().pose);
359 
360  double dt = 0.1;
361 
362  addPose(start); // add starting point with given orientation
363  setPoseVertexFixed(0,true); // StartConf is a fixed constraint during optimization
364 
365  bool backwards = false;
366  if (guess_backwards_motion && (goal.position()-start.position()).dot(start.orientationUnitVec()) < 0) // check if the goal is behind the start pose (w.r.t. start orientation)
367  backwards = true;
368  // TODO: dt ~ max_vel_x_backwards for backwards motions
369 
370  for (int i=1; i<(int)plan.size()-1; ++i)
371  {
372  double yaw;
373  if (estimate_orient)
374  {
375  // get yaw from the orientation of the distance vector between pose_{i+1} and pose_{i}
376  double dx = plan[i+1].pose.position.x - plan[i].pose.position.x;
377  double dy = plan[i+1].pose.position.y - plan[i].pose.position.y;
378  yaw = std::atan2(dy,dx);
379  if (backwards)
380  yaw = g2o::normalize_theta(yaw+M_PI);
381  }
382  else
383  {
384  yaw = tf::getYaw(plan[i].pose.orientation);
385  }
386  PoseSE2 intermediate_pose(plan[i].pose.position.x, plan[i].pose.position.y, yaw);
387  if (max_vel_x > 0) dt = (intermediate_pose.position()-BackPose().position()).norm()/max_vel_x;
388  addPoseAndTimeDiff(intermediate_pose, dt);
389  }
390 
391  // if number of samples is not larger than min_samples, insert manually
392  if ( sizePoses() < min_samples-1 )
393  {
394  ROS_DEBUG("initTEBtoGoal(): number of generated samples is less than specified by min_samples. Forcing the insertion of more samples...");
395  while (sizePoses() < min_samples-1) // subtract goal point that will be added later
396  {
397  // simple strategy: interpolate between the current pose and the goal
398  PoseSE2 intermediate_pose = PoseSE2::average(BackPose(), goal);
399  if (max_vel_x > 0) dt = (intermediate_pose.position()-BackPose().position()).norm()/max_vel_x;
400  addPoseAndTimeDiff( intermediate_pose, dt ); // let the optimier correct the timestep (TODO: better initialization
401  }
402  }
403 
404  // Now add final state with given orientation
405  if (max_vel_x > 0) dt = (goal.position()-BackPose().position()).norm()/max_vel_x;
406  addPoseAndTimeDiff(goal, dt);
407  setPoseVertexFixed(sizePoses()-1,true); // GoalConf is a fixed constraint during optimization
408  }
409  else // size!=0
410  {
411  ROS_WARN("Cannot init TEB between given configuration and goal, because TEB vectors are not empty or TEB is already initialized (call this function before adding states yourself)!");
412  ROS_WARN("Number of TEB configurations: %d, Number of TEB timediffs: %d", sizePoses(), sizeTimeDiffs());
413  return false;
414  }
415 
416  return true;
417 }
418 
419 
420 int TimedElasticBand::findClosestTrajectoryPose(const Eigen::Ref<const Eigen::Vector2d>& ref_point, double* distance, int begin_idx) const
421 {
422  std::vector<double> dist_vec; // TODO: improve! efficiency
423  dist_vec.reserve(sizePoses());
424 
425  int n = sizePoses();
426 
427  // calc distances
428  for (int i = begin_idx; i < n; i++)
429  {
430  Eigen::Vector2d diff = ref_point - Pose(i).position();
431  dist_vec.push_back(diff.norm());
432  }
433 
434  if (dist_vec.empty())
435  return -1;
436 
437  // find minimum
438  int index_min = 0;
439 
440  double last_value = dist_vec.at(0);
441  for (int i=1; i < (int)dist_vec.size(); i++)
442  {
443  if (dist_vec.at(i) < last_value)
444  {
445  last_value = dist_vec.at(i);
446  index_min = i;
447  }
448  }
449  if (distance)
450  *distance = last_value;
451  return begin_idx+index_min;
452 }
453 
454 
455 int TimedElasticBand::findClosestTrajectoryPose(const Eigen::Ref<const Eigen::Vector2d>& ref_line_start, const Eigen::Ref<const Eigen::Vector2d>& ref_line_end, double* distance) const
456 {
457  std::vector<double> dist_vec; // TODO: improve! efficiency
458  dist_vec.reserve(sizePoses());
459 
460  int n = sizePoses();
461 
462  // calc distances
463  for (int i = 0; i < n; i++)
464  {
465  Eigen::Vector2d point = Pose(i).position();
466  double diff = distance_point_to_segment_2d(point, ref_line_start, ref_line_end);
467  dist_vec.push_back(diff);
468  }
469 
470  if (dist_vec.empty())
471  return -1;
472 
473  // find minimum
474  int index_min = 0;
475 
476  double last_value = dist_vec.at(0);
477  for (int i=1; i < (int)dist_vec.size(); i++)
478  {
479  if (dist_vec.at(i) < last_value)
480  {
481  last_value = dist_vec.at(i);
482  index_min = i;
483  }
484  }
485  if (distance)
486  *distance = last_value;
487  return index_min; // return index, because it's equal to the vertex, which represents this bandpoint
488 }
489 
491 {
492  if (vertices.empty())
493  return 0;
494  else if (vertices.size() == 1)
495  return findClosestTrajectoryPose(vertices.front());
496  else if (vertices.size() == 2)
497  return findClosestTrajectoryPose(vertices.front(), vertices.back());
498 
499  std::vector<double> dist_vec; // TODO: improve! efficiency
500  dist_vec.reserve(sizePoses());
501 
502  int n = sizePoses();
503 
504  // calc distances
505  for (int i = 0; i < n; i++)
506  {
507  Eigen::Vector2d point = Pose(i).position();
508  double diff = HUGE_VAL;
509  for (int j = 0; j < (int) vertices.size()-1; ++j)
510  {
511  diff = std::min(diff, distance_point_to_segment_2d(point, vertices[j], vertices[j+1]));
512  }
513  diff = std::min(diff, distance_point_to_segment_2d(point, vertices.back(), vertices.front()));
514  dist_vec.push_back(diff);
515  }
516 
517  if (dist_vec.empty())
518  return -1;
519 
520  // find minimum
521  int index_min = 0;
522 
523  double last_value = dist_vec.at(0);
524  for (int i=1; i < (int)dist_vec.size(); i++)
525  {
526  if (dist_vec.at(i) < last_value)
527  {
528  last_value = dist_vec.at(i);
529  index_min = i;
530  }
531  }
532  if (distance)
533  *distance = last_value;
534  return index_min; // return index, because it's equal to the vertex, which represents this bandpoint
535 }
536 
537 
538 int TimedElasticBand::findClosestTrajectoryPose(const Obstacle& obstacle, double* distance) const
539 {
540  const PointObstacle* pobst = dynamic_cast<const PointObstacle*>(&obstacle);
541  if (pobst)
542  return findClosestTrajectoryPose(pobst->position(), distance);
543 
544  const LineObstacle* lobst = dynamic_cast<const LineObstacle*>(&obstacle);
545  if (lobst)
546  return findClosestTrajectoryPose(lobst->start(), lobst->end(), distance);
547 
548  const PolygonObstacle* polyobst = dynamic_cast<const PolygonObstacle*>(&obstacle);
549  if (polyobst)
550  return findClosestTrajectoryPose(polyobst->vertices(), distance);
551 
552  return findClosestTrajectoryPose(obstacle.getCentroid(), distance);
553 }
554 
555 
556 void TimedElasticBand::updateAndPruneTEB(boost::optional<const PoseSE2&> new_start, boost::optional<const PoseSE2&> new_goal, int min_samples)
557 {
558  // first and simple approach: change only start confs (and virtual start conf for inital velocity)
559  // TEST if optimizer can handle this "hard" placement
560 
561  if (new_start && sizePoses()>0)
562  {
563  // find nearest state (using l2-norm) in order to prune the trajectory
564  // (remove already passed states)
565  double dist_cache = (new_start->position()- Pose(0).position()).norm();
566  double dist;
567  int lookahead = std::min<int>( sizePoses()-min_samples, 10); // satisfy min_samples, otherwise max 10 samples
568 
569  int nearest_idx = 0;
570  for (int i = 1; i<=lookahead; ++i)
571  {
572  dist = (new_start->position()- Pose(i).position()).norm();
573  if (dist<dist_cache)
574  {
575  dist_cache = dist;
576  nearest_idx = i;
577  }
578  else break;
579  }
580 
581  // prune trajectory at the beginning (and extrapolate sequences at the end if the horizon is fixed)
582  if (nearest_idx>0)
583  {
584  // nearest_idx is equal to the number of samples to be removed (since it counts from 0 ;-) )
585  // WARNING delete starting at pose 1, and overwrite the original pose(0) with new_start, since Pose(0) is fixed during optimization!
586  deletePoses(1, nearest_idx); // delete first states such that the closest state is the new first one
587  deleteTimeDiffs(1, nearest_idx); // delete corresponding time differences
588  }
589 
590  // update start
591  Pose(0) = *new_start;
592  }
593 
594  if (new_goal && sizePoses()>0)
595  {
596  BackPose() = *new_goal;
597  }
598 };
599 
600 
601 bool TimedElasticBand::isTrajectoryInsideRegion(double radius, double max_dist_behind_robot, int skip_poses)
602 {
603  if (sizePoses()<=0)
604  return true;
605 
606  double radius_sq = radius*radius;
607  double max_dist_behind_robot_sq = max_dist_behind_robot*max_dist_behind_robot;
608  Eigen::Vector2d robot_orient = Pose(0).orientationUnitVec();
609 
610  for (int i=1; i<sizePoses(); i=i+skip_poses+1)
611  {
612  Eigen::Vector2d dist_vec = Pose(i).position()-Pose(0).position();
613  double dist_sq = dist_vec.squaredNorm();
614 
615  if (dist_sq > radius_sq)
616  {
617  ROS_INFO("outside robot");
618  return false;
619  }
620 
621  // check behind the robot with a different distance, if specified (or >=0)
622  if (max_dist_behind_robot >= 0 && dist_vec.dot(robot_orient) < 0 && dist_sq > max_dist_behind_robot_sq)
623  {
624  ROS_INFO("outside robot behind");
625  return false;
626  }
627 
628  }
629  return true;
630 }
631 
632 
633 
634 
635 } // namespace teb_local_planner
void setTimeDiffVertexFixed(int index, bool status)
Set a timediff vertex at pos index of the timediff sequence to be fixed or unfixed during optimizatio...
void deleteTimeDiffs(int index, int number)
Delete multiple (number) time differences starting at pos. index in the timediff sequence.
double getAccumulatedDistance() const
Calculate the length (accumulated euclidean distance) of the trajectory.
void insertPose(int index, const PoseSE2 &pose)
Insert a new pose vertex at pos. index to the pose sequence.
virtual const Eigen::Vector2d & getCentroid() const =0
Get centroid coordinates of the obstacle.
Eigen::Vector2d & position()
Access the 2D position part.
Definition: pose_se2.h:145
PoseSequence pose_vec_
Internal container storing the sequence of optimzable pose vertices.
double getSumOfAllTimeDiffs() const
Calculate the total transition time (sum over all time intervals of the timediff sequence) ...
static double getYaw(const Quaternion &bt_q)
static PoseSE2 average(const PoseSE2 &pose1, const PoseSE2 &pose2)
Get the mean / average of two poses and return the result (static) For the position part: 0...
Definition: pose_se2.h:266
bool initTrajectoryToGoal(const PoseSE2 &start, const PoseSE2 &goal, double diststep=0, double max_vel_x=0.5, int min_samples=3, bool guess_backwards_motion=false)
Initialize a trajectory between a given start and goal pose.
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
void addPoseAndTimeDiff(const PoseSE2 &pose, double dt)
Append a (pose, timediff) vertex pair to the end of the current trajectory (pose and timediff sequenc...
double & x()
Access the x-coordinate the pose.
Definition: pose_se2.h:158
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > Point2dContainer
Abbrev. for a container storing 2d points.
PoseSE2 & BackPose()
Access the last PoseSE2 in the pose sequence.
void updateAndPruneTEB(boost::optional< const PoseSE2 & > new_start, boost::optional< const PoseSE2 & > new_goal, int min_samples=3)
Hot-Start from an existing trajectory with updated start and goal poses.
#define ROS_WARN(...)
void addPose(const PoseSE2 &pose, bool fixed=false)
Append a new pose vertex to the back of the pose sequence.
Implements a polygon obstacle with an arbitrary number of vertices.
Definition: obstacles.h:748
doubleAcc dot(const VectorAcc &lhs, const VectorAcc &rhs)
Implements a 2D line obstacle.
Definition: obstacles.h:597
int findClosestTrajectoryPose(const Eigen::Ref< const Eigen::Vector2d > &ref_point, double *distance=NULL, int begin_idx=0) const
Find the closest point on the trajectory w.r.t. to a provided reference point.
Eigen::Vector2d orientationUnitVec() const
Return the unit vector of the current orientation.
Definition: pose_se2.h:215
void deletePose(int index)
Delete pose at pos. index in the pose sequence.
void deletePoses(int index, int number)
Delete multiple (number) poses starting at pos. index in the pose sequence.
const Eigen::Vector2d & position() const
Return the current position of the obstacle (read-only)
Definition: obstacles.h:418
int sizeTimeDiffs() const
Get the length of the internal timediff sequence.
#define ROS_INFO(...)
double & TimeDiff(int index)
Access the time difference at pos index of the time sequence.
Implements a 2D point obstacle.
Definition: obstacles.h:305
bool isTrajectoryInsideRegion(double radius, double max_dist_behind_robot=-1, int skip_poses=0)
Check if all trajectory points are contained in a specific region.
TimeDiffSequence timediff_vec_
Internal container storing the sequence of optimzable timediff vertices.
double distance_point_to_segment_2d(const Eigen::Ref< const Eigen::Vector2d > &point, const Eigen::Ref< const Eigen::Vector2d > &line_start, const Eigen::Ref< const Eigen::Vector2d > &line_end)
Helper function to calculate the distance between a line segment and a point.
void clearTimedElasticBand()
clear all poses and timediffs from the trajectory. The pose and timediff sequences will be empty and ...
PoseSE2 & Pose(int index)
Access the pose at pos index of the pose sequence.
double & y()
Access the y-coordinate the pose.
Definition: pose_se2.h:170
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
Definition: pose_se2.h:57
virtual ~TimedElasticBand()
Destruct the class.
void addTimeDiff(double dt, bool fixed=false)
Append a new time difference vertex to the back of the time diff sequence.
This class stores and wraps a SE2 pose (position and orientation) into a vertex that can be optimized...
Definition: vertex_pose.h:63
void deleteTimeDiff(int index)
Delete pose at pos. index in the timediff sequence.
double getSumOfTimeDiffsUpToIdx(int index) const
Calculate the estimated transition time up to the pose denoted by index.
void setPoseVertexFixed(int index, bool status)
Set a pose vertex at pos index of the pose sequence to be fixed or unfixed during optimization...
#define ROS_ASSERT(cond)
void insertTimeDiff(int index, double dt)
Insert a new timediff vertex at pos. index to the timediff sequence.
void autoResize(double dt_ref, double dt_hysteresis, int min_samples=3, int max_samples=1000, bool fast_mode=false)
Resize the trajectory by removing or inserting a (pose,dt) pair depending on a reference temporal res...
int sizePoses() const
Get the length of the internal pose sequence.
#define ROS_ERROR(...)
bool isInit() const
Check whether the trajectory is initialized (nonzero pose and timediff sequences) ...
Abstract class that defines the interface for modelling obstacles.
Definition: obstacles.h:67
#define ROS_DEBUG(...)
This class stores and wraps a time difference into a vertex that can be optimized via g2o...


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Jun 3 2020 04:03:08