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 #include <limits>
42 
43 namespace teb_local_planner
44 {
45 
46 namespace
47 {
52  double estimateDeltaT(const PoseSE2& start, const PoseSE2& end,
53  double max_vel_x, double max_vel_theta)
54  {
55  double dt_constant_motion = 0.1;
56  if (max_vel_x > 0) {
57  double trans_dist = (end.position() - start.position()).norm();
58  dt_constant_motion = trans_dist / max_vel_x;
59  }
60  if (max_vel_theta > 0) {
61  double rot_dist = std::abs(g2o::normalize_theta(end.theta() - start.theta()));
62  dt_constant_motion = std::max(dt_constant_motion, rot_dist / max_vel_theta);
63  }
64  return dt_constant_motion;
65  }
66 } // namespace
67 
68 
70 {
71 }
72 
74 {
75  ROS_DEBUG("Destructor Timed_Elastic_Band...");
77 }
78 
79 
80 void TimedElasticBand::addPose(const PoseSE2& pose, bool fixed)
81 {
82  VertexPose* pose_vertex = new VertexPose(pose, fixed);
83  pose_vec_.push_back( pose_vertex );
84  return;
85 }
86 
87 void TimedElasticBand::addPose(const Eigen::Ref<const Eigen::Vector2d>& position, double theta, bool fixed)
88 {
89  VertexPose* pose_vertex = new VertexPose(position, theta, fixed);
90  pose_vec_.push_back( pose_vertex );
91  return;
92 }
93 
94  void TimedElasticBand::addPose(double x, double y, double theta, bool fixed)
95 {
96  VertexPose* pose_vertex = new VertexPose(x, y, theta, fixed);
97  pose_vec_.push_back( pose_vertex );
98  return;
99 }
100 
101 void TimedElasticBand::addTimeDiff(double dt, bool fixed)
102 {
103  ROS_ASSERT_MSG(dt > 0., "Adding a timediff requires a positive dt");
104  VertexTimeDiff* timediff_vertex = new VertexTimeDiff(dt, fixed);
105  timediff_vec_.push_back( timediff_vertex );
106  return;
107 }
108 
109 
110 void TimedElasticBand::addPoseAndTimeDiff(double x, double y, double angle, double dt)
111 {
112  if (sizePoses() != sizeTimeDiffs())
113  {
114  addPose(x,y,angle,false);
115  addTimeDiff(dt,false);
116  }
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 
123 
124 void TimedElasticBand::addPoseAndTimeDiff(const PoseSE2& pose, double dt)
125 {
126  if (sizePoses() != sizeTimeDiffs())
127  {
128  addPose(pose,false);
129  addTimeDiff(dt,false);
130  } else
131  ROS_ERROR("Method addPoseAndTimeDiff: Add one single Pose first. Timediff describes the time difference between last conf and given conf");
132  return;
133 }
134 
135 void TimedElasticBand::addPoseAndTimeDiff(const Eigen::Ref<const Eigen::Vector2d>& position, double theta, double dt)
136 {
138  {
139  addPose(position, theta,false);
140  addTimeDiff(dt,false);
141  } else
142  ROS_ERROR("Method addPoseAndTimeDiff: Add one single Pose first. Timediff describes the time difference between last conf and given conf");
143  return;
144 }
145 
146 
147 void TimedElasticBand::deletePose(int index)
148 {
149  ROS_ASSERT(index<pose_vec_.size());
150  delete pose_vec_.at(index);
151  pose_vec_.erase(pose_vec_.begin()+index);
152 }
153 
154 void TimedElasticBand::deletePoses(int index, int number)
155 {
156  ROS_ASSERT(index+number<=(int)pose_vec_.size());
157  for (int i = index; i<index+number; ++i)
158  delete pose_vec_.at(i);
159  pose_vec_.erase(pose_vec_.begin()+index, pose_vec_.begin()+index+number);
160 }
161 
162 void TimedElasticBand::deleteTimeDiff(int index)
163 {
164  ROS_ASSERT(index<(int)timediff_vec_.size());
165  delete timediff_vec_.at(index);
166  timediff_vec_.erase(timediff_vec_.begin()+index);
167 }
168 
169 void TimedElasticBand::deleteTimeDiffs(int index, int number)
170 {
171  ROS_ASSERT(index+number<=timediff_vec_.size());
172  for (int i = index; i<index+number; ++i)
173  delete timediff_vec_.at(i);
174  timediff_vec_.erase(timediff_vec_.begin()+index, timediff_vec_.begin()+index+number);
175 }
176 
177 void TimedElasticBand::insertPose(int index, const PoseSE2& pose)
178 {
179  VertexPose* pose_vertex = new VertexPose(pose);
180  pose_vec_.insert(pose_vec_.begin()+index, pose_vertex);
181 }
182 
183 void TimedElasticBand::insertPose(int index, const Eigen::Ref<const Eigen::Vector2d>& position, double theta)
184 {
185  VertexPose* pose_vertex = new VertexPose(position, theta);
186  pose_vec_.insert(pose_vec_.begin()+index, pose_vertex);
187 }
188 
189 void TimedElasticBand::insertPose(int index, double x, double y, double theta)
190 {
191  VertexPose* pose_vertex = new VertexPose(x, y, theta);
192  pose_vec_.insert(pose_vec_.begin()+index, pose_vertex);
193 }
194 
195 void TimedElasticBand::insertTimeDiff(int index, double dt)
196 {
197  VertexTimeDiff* timediff_vertex = new VertexTimeDiff(dt);
198  timediff_vec_.insert(timediff_vec_.begin()+index, timediff_vertex);
199 }
200 
201 
203 {
204  for (PoseSequence::iterator pose_it = pose_vec_.begin(); pose_it != pose_vec_.end(); ++pose_it)
205  delete *pose_it;
206  pose_vec_.clear();
207 
208  for (TimeDiffSequence::iterator dt_it = timediff_vec_.begin(); dt_it != timediff_vec_.end(); ++dt_it)
209  delete *dt_it;
210  timediff_vec_.clear();
211 }
212 
213 
214 void TimedElasticBand::setPoseVertexFixed(int index, bool status)
215 {
216  ROS_ASSERT(index<sizePoses());
217  pose_vec_.at(index)->setFixed(status);
218 }
219 
220 void TimedElasticBand::setTimeDiffVertexFixed(int index, bool status)
221 {
222  ROS_ASSERT(index<sizeTimeDiffs());
223  timediff_vec_.at(index)->setFixed(status);
224 }
225 
226 
227 void TimedElasticBand::autoResize(double dt_ref, double dt_hysteresis, int min_samples, int max_samples, bool fast_mode)
228 {
229  ROS_ASSERT(sizeTimeDiffs() == 0 || sizeTimeDiffs() + 1 == sizePoses());
231  bool modified = true;
232 
233  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.
234  {
235  modified = false;
236 
237  for(int i=0; i < sizeTimeDiffs(); ++i) // TimeDiff connects Point(i) with Point(i+1)
238  {
239  if(TimeDiff(i) > dt_ref + dt_hysteresis && sizeTimeDiffs()<max_samples)
240  {
241  // Force the planner to have equal timediffs between poses (dt_ref +/- dt_hyteresis).
242  // (new behaviour)
243  if (TimeDiff(i) > 2*dt_ref)
244  {
245  double newtime = 0.5*TimeDiff(i);
246 
247  TimeDiff(i) = newtime;
248  insertPose(i+1, PoseSE2::average(Pose(i),Pose(i+1)) );
249  insertTimeDiff(i+1,newtime);
250 
251  i--; // check the updated pose diff again
252  modified = true;
253  }
254  else
255  {
256  if (i < sizeTimeDiffs() - 1)
257  {
258  timediffs().at(i+1)->dt()+= timediffs().at(i)->dt() - dt_ref;
259  }
260  timediffs().at(i)->dt() = dt_ref;
261  }
262  }
263  else if(TimeDiff(i) < dt_ref - dt_hysteresis && sizeTimeDiffs()>min_samples) // only remove samples if size is larger than min_samples.
264  {
265  //ROS_DEBUG("teb_local_planner: autoResize() deleting bandpoint i=%u, #TimeDiffs=%lu",i,sizeTimeDiffs());
266 
267  if(i < ((int)sizeTimeDiffs()-1))
268  {
269  TimeDiff(i+1) = TimeDiff(i+1) + TimeDiff(i);
270  deleteTimeDiff(i);
271  deletePose(i+1);
272  i--; // check the updated pose diff again
273  }
274  else
275  { // last motion should be adjusted, shift time to the interval before
276  TimeDiff(i-1) += TimeDiff(i);
277  deleteTimeDiff(i);
278  deletePose(i);
279  }
280 
281  modified = true;
282  }
283  }
284  if (fast_mode) break;
285  }
286 }
287 
288 
290 {
291  double time = 0;
292 
293  for(TimeDiffSequence::const_iterator dt_it = timediff_vec_.begin(); dt_it != timediff_vec_.end(); ++dt_it)
294  {
295  time += (*dt_it)->dt();
296  }
297  return time;
298 }
299 
300 double TimedElasticBand::getSumOfTimeDiffsUpToIdx(int index) const
301 {
302  ROS_ASSERT(index<=timediff_vec_.size());
303 
304  double time = 0;
305 
306  for(int i = 0; i < index; ++i)
307  {
308  time += timediff_vec_.at(i)->dt();
309  }
310 
311  return time;
312 }
313 
315 {
316  double dist = 0;
317 
318  for(int i=1; i<sizePoses(); ++i)
319  {
320  dist += (Pose(i).position() - Pose(i-1).position()).norm();
321  }
322  return dist;
323 }
324 
325 bool TimedElasticBand::initTrajectoryToGoal(const PoseSE2& start, const PoseSE2& goal, double diststep, double max_vel_x, int min_samples, bool guess_backwards_motion)
326 {
327  if (!isInit())
328  {
329  addPose(start); // add starting point
330  setPoseVertexFixed(0,true); // StartConf is a fixed constraint during optimization
331 
332  double timestep = 0.1;
333 
334  if (diststep!=0)
335  {
336  Eigen::Vector2d point_to_goal = goal.position()-start.position();
337  double dir_to_goal = std::atan2(point_to_goal[1],point_to_goal[0]); // direction to goal
338  double dx = diststep*std::cos(dir_to_goal);
339  double dy = diststep*std::sin(dir_to_goal);
340  double orient_init = dir_to_goal;
341  // check if the goal is behind the start pose (w.r.t. start orientation)
342  if (guess_backwards_motion && point_to_goal.dot(start.orientationUnitVec()) < 0)
343  orient_init = g2o::normalize_theta(orient_init+M_PI);
344  // TODO: timestep ~ max_vel_x_backwards for backwards motions
345 
346  double dist_to_goal = point_to_goal.norm();
347  double no_steps_d = dist_to_goal/std::abs(diststep); // ignore negative values
348  unsigned int no_steps = (unsigned int) std::floor(no_steps_d);
349 
350  if (max_vel_x > 0) timestep = diststep / max_vel_x;
351 
352  for (unsigned int i=1; i<=no_steps; i++) // start with 1! starting point had index 0
353  {
354  if (i==no_steps && no_steps_d==(float) no_steps)
355  break; // if last conf (depending on stepsize) is equal to goal conf -> leave loop
356  addPoseAndTimeDiff(start.x()+i*dx,start.y()+i*dy,orient_init,timestep);
357  }
358 
359  }
360 
361  // if number of samples is not larger than min_samples, insert manually
362  if ( sizePoses() < min_samples-1 )
363  {
364  ROS_DEBUG("initTEBtoGoal(): number of generated samples is less than specified by min_samples. Forcing the insertion of more samples...");
365  while (sizePoses() < min_samples-1) // subtract goal point that will be added later
366  {
367  // simple strategy: interpolate between the current pose and the goal
368  PoseSE2 intermediate_pose = PoseSE2::average(BackPose(), goal);
369  if (max_vel_x > 0) timestep = (intermediate_pose.position()-BackPose().position()).norm()/max_vel_x;
370  addPoseAndTimeDiff( intermediate_pose, timestep ); // let the optimier correct the timestep (TODO: better initialization
371  }
372  }
373 
374  // add goal
375  if (max_vel_x > 0) timestep = (goal.position()-BackPose().position()).norm()/max_vel_x;
376  addPoseAndTimeDiff(goal,timestep); // add goal point
377  setPoseVertexFixed(sizePoses()-1,true); // GoalConf is a fixed constraint during optimization
378  }
379  else // size!=0
380  {
381  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)!");
382  ROS_WARN("Number of TEB configurations: %d, Number of TEB timediffs: %d",(unsigned int) sizePoses(),(unsigned int) sizeTimeDiffs());
383  return false;
384  }
385  return true;
386 }
387 
388 
389 bool TimedElasticBand::initTrajectoryToGoal(const std::vector<geometry_msgs::PoseStamped>& plan, double max_vel_x, double max_vel_theta, bool estimate_orient, int min_samples, bool guess_backwards_motion)
390 {
391 
392  if (!isInit())
393  {
394  PoseSE2 start(plan.front().pose);
395  PoseSE2 goal(plan.back().pose);
396 
397  addPose(start); // add starting point with given orientation
398  setPoseVertexFixed(0,true); // StartConf is a fixed constraint during optimization
399 
400  bool backwards = false;
401  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)
402  backwards = true;
403  // TODO: dt ~ max_vel_x_backwards for backwards motions
404 
405  for (int i=1; i<(int)plan.size()-1; ++i)
406  {
407  double yaw;
408  if (estimate_orient)
409  {
410  // get yaw from the orientation of the distance vector between pose_{i+1} and pose_{i}
411  double dx = plan[i+1].pose.position.x - plan[i].pose.position.x;
412  double dy = plan[i+1].pose.position.y - plan[i].pose.position.y;
413  yaw = std::atan2(dy,dx);
414  if (backwards)
415  yaw = g2o::normalize_theta(yaw+M_PI);
416  }
417  else
418  {
419  yaw = tf::getYaw(plan[i].pose.orientation);
420  }
421  PoseSE2 intermediate_pose(plan[i].pose.position.x, plan[i].pose.position.y, yaw);
422  double dt = estimateDeltaT(BackPose(), intermediate_pose, max_vel_x, max_vel_theta);
423  addPoseAndTimeDiff(intermediate_pose, dt);
424  }
425 
426  // if number of samples is not larger than min_samples, insert manually
427  if ( sizePoses() < min_samples-1 )
428  {
429  ROS_DEBUG("initTEBtoGoal(): number of generated samples is less than specified by min_samples. Forcing the insertion of more samples...");
430  while (sizePoses() < min_samples-1) // subtract goal point that will be added later
431  {
432  // simple strategy: interpolate between the current pose and the goal
433  PoseSE2 intermediate_pose = PoseSE2::average(BackPose(), goal);
434  double dt = estimateDeltaT(BackPose(), intermediate_pose, max_vel_x, max_vel_theta);
435  addPoseAndTimeDiff( intermediate_pose, dt ); // let the optimier correct the timestep (TODO: better initialization
436  }
437  }
438 
439  // Now add final state with given orientation
440  double dt = estimateDeltaT(BackPose(), goal, max_vel_x, max_vel_theta);
441  addPoseAndTimeDiff(goal, dt);
442  setPoseVertexFixed(sizePoses()-1,true); // GoalConf is a fixed constraint during optimization
443  }
444  else // size!=0
445  {
446  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)!");
447  ROS_WARN("Number of TEB configurations: %d, Number of TEB timediffs: %d", sizePoses(), sizeTimeDiffs());
448  return false;
449  }
450 
451  return true;
452 }
453 
454 
455 int TimedElasticBand::findClosestTrajectoryPose(const Eigen::Ref<const Eigen::Vector2d>& ref_point, double* distance, int begin_idx) const
456 {
457  int n = sizePoses();
458  if (begin_idx < 0 || begin_idx >= n)
459  return -1;
460 
461  double min_dist_sq = std::numeric_limits<double>::max();
462  int min_idx = -1;
463 
464  for (int i = begin_idx; i < n; i++)
465  {
466  double dist_sq = (ref_point - Pose(i).position()).squaredNorm();
467  if (dist_sq < min_dist_sq)
468  {
469  min_dist_sq = dist_sq;
470  min_idx = i;
471  }
472  }
473 
474  if (distance)
475  *distance = std::sqrt(min_dist_sq);
476 
477  return min_idx;
478 }
479 
480 
481 int TimedElasticBand::findClosestTrajectoryPose(const Eigen::Ref<const Eigen::Vector2d>& ref_line_start, const Eigen::Ref<const Eigen::Vector2d>& ref_line_end, double* distance) const
482 {
483  double min_dist = std::numeric_limits<double>::max();
484  int min_idx = -1;
485 
486  for (int i = 0; i < sizePoses(); i++)
487  {
488  Eigen::Vector2d point = Pose(i).position();
489  double dist = distance_point_to_segment_2d(point, ref_line_start, ref_line_end);
490  if (dist < min_dist)
491  {
492  min_dist = dist;
493  min_idx = i;
494  }
495  }
496 
497  if (distance)
498  *distance = min_dist;
499  return min_idx;
500 }
501 
503 {
504  if (vertices.empty())
505  return 0;
506  else if (vertices.size() == 1)
507  return findClosestTrajectoryPose(vertices.front());
508  else if (vertices.size() == 2)
509  return findClosestTrajectoryPose(vertices.front(), vertices.back());
510 
511  double min_dist = std::numeric_limits<double>::max();
512  int min_idx = -1;
513 
514  for (int i = 0; i < sizePoses(); i++)
515  {
516  Eigen::Vector2d point = Pose(i).position();
517  double dist_to_polygon = std::numeric_limits<double>::max();
518  for (int j = 0; j < (int) vertices.size()-1; ++j)
519  {
520  dist_to_polygon = std::min(dist_to_polygon, distance_point_to_segment_2d(point, vertices[j], vertices[j+1]));
521  }
522  dist_to_polygon = std::min(dist_to_polygon, distance_point_to_segment_2d(point, vertices.back(), vertices.front()));
523  if (dist_to_polygon < min_dist)
524  {
525  min_dist = dist_to_polygon;
526  min_idx = i;
527  }
528  }
529 
530  if (distance)
531  *distance = min_dist;
532 
533  return min_idx;
534 }
535 
536 
537 int TimedElasticBand::findClosestTrajectoryPose(const Obstacle& obstacle, double* distance) const
538 {
539  const PointObstacle* pobst = dynamic_cast<const PointObstacle*>(&obstacle);
540  if (pobst)
541  return findClosestTrajectoryPose(pobst->position(), distance);
542 
543  const LineObstacle* lobst = dynamic_cast<const LineObstacle*>(&obstacle);
544  if (lobst)
545  return findClosestTrajectoryPose(lobst->start(), lobst->end(), distance);
546 
547  const PolygonObstacle* polyobst = dynamic_cast<const PolygonObstacle*>(&obstacle);
548  if (polyobst)
549  return findClosestTrajectoryPose(polyobst->vertices(), distance);
550 
551  return findClosestTrajectoryPose(obstacle.getCentroid(), distance);
552 }
553 
554 
555 void TimedElasticBand::updateAndPruneTEB(boost::optional<const PoseSE2&> new_start, boost::optional<const PoseSE2&> new_goal, int min_samples)
556 {
557  // first and simple approach: change only start confs (and virtual start conf for inital velocity)
558  // TEST if optimizer can handle this "hard" placement
559 
560  if (new_start && sizePoses()>0)
561  {
562  // find nearest state (using l2-norm) in order to prune the trajectory
563  // (remove already passed states)
564  double dist_cache = (new_start->position()- Pose(0).position()).norm();
565  double dist;
566  int lookahead = std::min<int>( sizePoses()-min_samples, 10); // satisfy min_samples, otherwise max 10 samples
567 
568  int nearest_idx = 0;
569  for (int i = 1; i<=lookahead; ++i)
570  {
571  dist = (new_start->position()- Pose(i).position()).norm();
572  if (dist<dist_cache)
573  {
574  dist_cache = dist;
575  nearest_idx = i;
576  }
577  else break;
578  }
579 
580  // prune trajectory at the beginning (and extrapolate sequences at the end if the horizon is fixed)
581  if (nearest_idx>0)
582  {
583  // nearest_idx is equal to the number of samples to be removed (since it counts from 0 ;-) )
584  // WARNING delete starting at pose 1, and overwrite the original pose(0) with new_start, since Pose(0) is fixed during optimization!
585  deletePoses(1, nearest_idx); // delete first states such that the closest state is the new first one
586  deleteTimeDiffs(1, nearest_idx); // delete corresponding time differences
587  }
588 
589  // update start
590  Pose(0) = *new_start;
591  }
592 
593  if (new_goal && sizePoses()>0)
594  {
595  BackPose() = *new_goal;
596  }
597 };
598 
599 
600 bool TimedElasticBand::isTrajectoryInsideRegion(double radius, double max_dist_behind_robot, int skip_poses)
601 {
602  if (sizePoses()<=0)
603  return true;
604 
605  double radius_sq = radius*radius;
606  double max_dist_behind_robot_sq = max_dist_behind_robot*max_dist_behind_robot;
607  Eigen::Vector2d robot_orient = Pose(0).orientationUnitVec();
608 
609  for (int i=1; i<sizePoses(); i=i+skip_poses+1)
610  {
611  Eigen::Vector2d dist_vec = Pose(i).position()-Pose(0).position();
612  double dist_sq = dist_vec.squaredNorm();
613 
614  if (dist_sq > radius_sq)
615  {
616  ROS_INFO("outside robot");
617  return false;
618  }
619 
620  // check behind the robot with a different distance, if specified (or >=0)
621  if (max_dist_behind_robot >= 0 && dist_vec.dot(robot_orient) < 0 && dist_sq > max_dist_behind_robot_sq)
622  {
623  ROS_INFO("outside robot behind");
624  return false;
625  }
626 
627  }
628  return true;
629 }
630 
631 
632 
633 
634 } // namespace teb_local_planner
teb_local_planner::TimedElasticBand::isTrajectoryInsideRegion
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.
Definition: timed_elastic_band.cpp:636
teb_local_planner::TimedElasticBand::Pose
PoseSE2 & Pose(int index)
Access the pose at pos index of the pose sequence.
Definition: timed_elastic_band.h:192
teb_local_planner::TimedElasticBand::deleteTimeDiffs
void deleteTimeDiffs(int index, int number)
Delete multiple (number) time differences starting at pos. index in the timediff sequence.
Definition: timed_elastic_band.cpp:205
teb_local_planner::TimedElasticBand::timediff_vec_
TimeDiffSequence timediff_vec_
Internal container storing the sequence of optimzable timediff vertices.
Definition: timed_elastic_band.h:682
teb_local_planner::TimedElasticBand::TimeDiff
double & TimeDiff(int index)
Access the time difference at pos index of the time sequence.
Definition: timed_elastic_band.h:170
teb_local_planner::Point2dContainer
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > Point2dContainer
Abbrev. for a container storing 2d points.
Definition: distance_calculations.h:86
teb_local_planner::TimedElasticBand::insertTimeDiff
void insertTimeDiff(int index, double dt)
Insert a new timediff vertex at pos. index to the timediff sequence.
Definition: timed_elastic_band.cpp:231
teb_local_planner::TimedElasticBand::~TimedElasticBand
virtual ~TimedElasticBand()
Destruct the class.
Definition: timed_elastic_band.cpp:109
teb_local_planner::TimedElasticBand::isInit
bool isInit() const
Check whether the trajectory is initialized (nonzero pose and timediff sequences)
Definition: timed_elastic_band.h:645
teb_local_planner::TimedElasticBand::addPoseAndTimeDiff
void addPoseAndTimeDiff(const PoseSE2 &pose, double dt)
Append a (pose, timediff) vertex pair to the end of the current trajectory (pose and timediff sequenc...
Definition: timed_elastic_band.cpp:160
teb_local_planner::TimedElasticBand::BackPose
PoseSE2 & BackPose()
Access the last PoseSE2 in the pose sequence.
Definition: timed_elastic_band.h:212
teb_local_planner::TimedElasticBand::addTimeDiff
void addTimeDiff(double dt, bool fixed=false)
Append a new time difference vertex to the back of the time diff sequence.
Definition: timed_elastic_band.cpp:137
teb_local_planner::TimedElasticBand::addPose
void addPose(const PoseSE2 &pose, bool fixed=false)
Append a new pose vertex to the back of the pose sequence.
Definition: timed_elastic_band.cpp:116
teb_local_planner::TimedElasticBand::findClosestTrajectoryPose
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.
Definition: timed_elastic_band.cpp:491
teb_local_planner::TimedElasticBand::setPoseVertexFixed
void setPoseVertexFixed(int index, bool status)
Set a pose vertex at pos index of the pose sequence to be fixed or unfixed during optimization.
Definition: timed_elastic_band.cpp:250
tf::getYaw
static double getYaw(const geometry_msgs::Quaternion &msg_q)
export_to_svg.point
list point
Definition: export_to_svg.py:223
teb_local_planner::VertexTimeDiff
This class stores and wraps a time difference into a vertex that can be optimized via g2o.
Definition: vertex_timediff.h:102
teb_local_planner::TimedElasticBand::getSumOfTimeDiffsUpToIdx
double getSumOfTimeDiffsUpToIdx(int index) const
Calculate the estimated transition time up to the pose denoted by index.
Definition: timed_elastic_band.cpp:336
teb_local_planner::TimedElasticBand::deletePoses
void deletePoses(int index, int number)
Delete multiple (number) poses starting at pos. index in the pose sequence.
Definition: timed_elastic_band.cpp:190
teb_local_planner::TimedElasticBand::updateAndPruneTEB
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.
Definition: timed_elastic_band.cpp:591
ROS_DEBUG
#define ROS_DEBUG(...)
angle
double angle(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
teb_local_planner::distance_point_to_segment_2d
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.
Definition: distance_calculations.h:119
teb_local_planner::TimedElasticBand::insertPose
void insertPose(int index, const PoseSE2 &pose)
Insert a new pose vertex at pos. index to the pose sequence.
Definition: timed_elastic_band.cpp:213
timed_elastic_band.h
teb_local_planner::PoseSE2::position
Eigen::Vector2d & position()
Access the 2D position part.
Definition: pose_se2.h:181
ROS_ASSERT_MSG
#define ROS_ASSERT_MSG(cond,...)
ROS_WARN
#define ROS_WARN(...)
teb_local_planner::TimedElasticBand::sizePoses
int sizePoses() const
Get the length of the internal pose sequence.
Definition: timed_elastic_band.h:635
export_to_svg.vertices
list vertices
Definition: export_to_svg.py:233
distance
double distance(double x0, double y0, double x1, double y1)
teb_local_planner::TimedElasticBand::deletePose
void deletePose(int index)
Delete pose at pos. index in the pose sequence.
Definition: timed_elastic_band.cpp:183
teb_local_planner::PointObstacle
Implements a 2D point obstacle.
Definition: obstacles.h:341
start
ROSCPP_DECL void start()
teb_local_planner::TimedElasticBand::initTrajectoryToGoal
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.
Definition: timed_elastic_band.cpp:361
teb_local_planner::LineObstacle::start
const Eigen::Vector2d & start() const
Definition: obstacles.h:746
teb_local_planner::PoseSE2
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:93
teb_local_planner::PoseSE2::orientationUnitVec
Eigen::Vector2d orientationUnitVec() const
Return the unit vector of the current orientation.
Definition: pose_se2.h:251
teb_local_planner::LineObstacle::end
const Eigen::Vector2d & end() const
Definition: obstacles.h:748
teb_local_planner::TimedElasticBand::sizeTimeDiffs
int sizeTimeDiffs() const
Get the length of the internal timediff sequence.
Definition: timed_elastic_band.h:640
teb_local_planner::LineObstacle
Implements a 2D line obstacle.
Definition: obstacles.h:633
teb_local_planner::TimedElasticBand::timediffs
TimeDiffSequence & timediffs()
Access the complete timediff sequence.
Definition: timed_elastic_band.h:157
ROS_ERROR
#define ROS_ERROR(...)
teb_local_planner::TimedElasticBand::pose_vec_
PoseSequence pose_vec_
Internal container storing the sequence of optimzable pose vertices.
Definition: timed_elastic_band.h:681
teb_local_planner::PoseSE2::average
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:302
teb_local_planner::TimedElasticBand::getAccumulatedDistance
double getAccumulatedDistance() const
Calculate the length (accumulated euclidean distance) of the trajectory.
Definition: timed_elastic_band.cpp:350
teb_local_planner::TimedElasticBand::deleteTimeDiff
void deleteTimeDiff(int index)
Delete pose at pos. index in the timediff sequence.
Definition: timed_elastic_band.cpp:198
teb_local_planner::TimedElasticBand::TimedElasticBand
TimedElasticBand()
Construct the class.
Definition: timed_elastic_band.cpp:105
teb_local_planner::PolygonObstacle
Implements a polygon obstacle with an arbitrary number of vertices.
Definition: obstacles.h:934
ROS_INFO
#define ROS_INFO(...)
ROS_ASSERT
#define ROS_ASSERT(cond)
teb_local_planner
Definition: distance_calculations.h:46
teb_local_planner::VertexPose
This class stores and wraps a SE2 pose (position and orientation) into a vertex that can be optimized...
Definition: vertex_pose.h:104
teb_local_planner::TimedElasticBand::clearTimedElasticBand
void clearTimedElasticBand()
clear all poses and timediffs from the trajectory. The pose and timediff sequences will be empty and ...
Definition: timed_elastic_band.cpp:238
teb_local_planner::TimedElasticBand::autoResize
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...
Definition: timed_elastic_band.cpp:263
teb_local_planner::TimedElasticBand::setTimeDiffVertexFixed
void setTimeDiffVertexFixed(int index, bool status)
Set a timediff vertex at pos index of the timediff sequence to be fixed or unfixed during optimizatio...
Definition: timed_elastic_band.cpp:256
teb_local_planner::TimedElasticBand::getSumOfAllTimeDiffs
double getSumOfAllTimeDiffs() const
Calculate the total transition time (sum over all time intervals of the timediff sequence)
Definition: timed_elastic_band.cpp:325


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sun Jan 7 2024 03:45:15