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 {
206 
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 
238  modified = true;
239  }
240  }
241  if (fast_mode) break;
242  }
243 }
244 
245 
247 {
248  double time = 0;
249 
250  for(TimeDiffSequence::const_iterator dt_it = timediff_vec_.begin(); dt_it != timediff_vec_.end(); ++dt_it)
251  {
252  time += (*dt_it)->dt();
253  }
254  return time;
255 }
256 
258 {
259  ROS_ASSERT(index<=timediff_vec_.size());
260 
261  double time = 0;
262 
263  for(int i = 0; i < index; ++i)
264  {
265  time += timediff_vec_.at(i)->dt();
266  }
267 
268  return time;
269 }
270 
272 {
273  double dist = 0;
274 
275  for(int i=1; i<sizePoses(); ++i)
276  {
277  dist += (Pose(i).position() - Pose(i-1).position()).norm();
278  }
279  return dist;
280 }
281 
282 bool TimedElasticBand::initTrajectoryToGoal(const PoseSE2& start, const PoseSE2& goal, double diststep, double max_vel_x, int min_samples, bool guess_backwards_motion)
283 {
284  if (!isInit())
285  {
286  addPose(start); // add starting point
287  setPoseVertexFixed(0,true); // StartConf is a fixed constraint during optimization
288 
289  double timestep = 0.1;
290 
291  if (diststep!=0)
292  {
293  Eigen::Vector2d point_to_goal = goal.position()-start.position();
294  double dir_to_goal = std::atan2(point_to_goal[1],point_to_goal[0]); // direction to goal
295  double dx = diststep*std::cos(dir_to_goal);
296  double dy = diststep*std::sin(dir_to_goal);
297  double orient_init = dir_to_goal;
298  // check if the goal is behind the start pose (w.r.t. start orientation)
299  if (guess_backwards_motion && point_to_goal.dot(start.orientationUnitVec()) < 0)
300  orient_init = g2o::normalize_theta(orient_init+M_PI);
301  // TODO: timestep ~ max_vel_x_backwards for backwards motions
302 
303  double dist_to_goal = point_to_goal.norm();
304  double no_steps_d = dist_to_goal/std::abs(diststep); // ignore negative values
305  unsigned int no_steps = (unsigned int) std::floor(no_steps_d);
306 
307  if (max_vel_x > 0) timestep = diststep / max_vel_x;
308 
309  for (unsigned int i=1; i<=no_steps; i++) // start with 1! starting point had index 0
310  {
311  if (i==no_steps && no_steps_d==(float) no_steps)
312  break; // if last conf (depending on stepsize) is equal to goal conf -> leave loop
313  addPoseAndTimeDiff(start.x()+i*dx,start.y()+i*dy,orient_init,timestep);
314  }
315 
316  }
317 
318  // if number of samples is not larger than min_samples, insert manually
319  if ( sizePoses() < min_samples-1 )
320  {
321  ROS_DEBUG("initTEBtoGoal(): number of generated samples is less than specified by min_samples. Forcing the insertion of more samples...");
322  while (sizePoses() < min_samples-1) // subtract goal point that will be added later
323  {
324  // simple strategy: interpolate between the current pose and the goal
325  PoseSE2 intermediate_pose = PoseSE2::average(BackPose(), goal);
326  if (max_vel_x > 0) timestep = (intermediate_pose.position()-BackPose().position()).norm()/max_vel_x;
327  addPoseAndTimeDiff( intermediate_pose, timestep ); // let the optimier correct the timestep (TODO: better initialization
328  }
329  }
330 
331  // add goal
332  if (max_vel_x > 0) timestep = (goal.position()-BackPose().position()).norm()/max_vel_x;
333  addPoseAndTimeDiff(goal,timestep); // add goal point
334  setPoseVertexFixed(sizePoses()-1,true); // GoalConf is a fixed constraint during optimization
335  }
336  else // size!=0
337  {
338  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)!");
339  ROS_WARN("Number of TEB configurations: %d, Number of TEB timediffs: %d",(unsigned int) sizePoses(),(unsigned int) sizeTimeDiffs());
340  return false;
341  }
342  return true;
343 }
344 
345 
346 bool TimedElasticBand::initTrajectoryToGoal(const std::vector<geometry_msgs::PoseStamped>& plan, double max_vel_x, bool estimate_orient, int min_samples, bool guess_backwards_motion)
347 {
348 
349  if (!isInit())
350  {
351  PoseSE2 start(plan.front().pose);
352  PoseSE2 goal(plan.back().pose);
353 
354  double dt = 0.1;
355 
356  addPose(start); // add starting point with given orientation
357  setPoseVertexFixed(0,true); // StartConf is a fixed constraint during optimization
358 
359  bool backwards = false;
360  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)
361  backwards = true;
362  // TODO: dt ~ max_vel_x_backwards for backwards motions
363 
364  for (int i=1; i<(int)plan.size()-1; ++i)
365  {
366  double yaw;
367  if (estimate_orient)
368  {
369  // get yaw from the orientation of the distance vector between pose_{i+1} and pose_{i}
370  double dx = plan[i+1].pose.position.x - plan[i].pose.position.x;
371  double dy = plan[i+1].pose.position.y - plan[i].pose.position.y;
372  yaw = std::atan2(dy,dx);
373  if (backwards)
374  yaw = g2o::normalize_theta(yaw+M_PI);
375  }
376  else
377  {
378  yaw = tf::getYaw(plan[i].pose.orientation);
379  }
380  PoseSE2 intermediate_pose(plan[i].pose.position.x, plan[i].pose.position.y, yaw);
381  if (max_vel_x > 0) dt = (intermediate_pose.position()-BackPose().position()).norm()/max_vel_x;
382  addPoseAndTimeDiff(intermediate_pose, dt);
383  }
384 
385  // if number of samples is not larger than min_samples, insert manually
386  if ( sizePoses() < min_samples-1 )
387  {
388  ROS_DEBUG("initTEBtoGoal(): number of generated samples is less than specified by min_samples. Forcing the insertion of more samples...");
389  while (sizePoses() < min_samples-1) // subtract goal point that will be added later
390  {
391  // simple strategy: interpolate between the current pose and the goal
392  PoseSE2 intermediate_pose = PoseSE2::average(BackPose(), goal);
393  if (max_vel_x > 0) dt = (intermediate_pose.position()-BackPose().position()).norm()/max_vel_x;
394  addPoseAndTimeDiff( intermediate_pose, dt ); // let the optimier correct the timestep (TODO: better initialization
395  }
396  }
397 
398  // Now add final state with given orientation
399  if (max_vel_x > 0) dt = (goal.position()-BackPose().position()).norm()/max_vel_x;
400  addPoseAndTimeDiff(goal, dt);
401  setPoseVertexFixed(sizePoses()-1,true); // GoalConf is a fixed constraint during optimization
402  }
403  else // size!=0
404  {
405  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)!");
406  ROS_WARN("Number of TEB configurations: %d, Number of TEB timediffs: %d", sizePoses(), sizeTimeDiffs());
407  return false;
408  }
409 
410  return true;
411 }
412 
413 
414 int TimedElasticBand::findClosestTrajectoryPose(const Eigen::Ref<const Eigen::Vector2d>& ref_point, double* distance, int begin_idx) const
415 {
416  std::vector<double> dist_vec; // TODO: improve! efficiency
417  dist_vec.reserve(sizePoses());
418 
419  int n = sizePoses();
420 
421  // calc distances
422  for (int i = begin_idx; i < n; i++)
423  {
424  Eigen::Vector2d diff = ref_point - Pose(i).position();
425  dist_vec.push_back(diff.norm());
426  }
427 
428  if (dist_vec.empty())
429  return -1;
430 
431  // find minimum
432  int index_min = 0;
433 
434  double last_value = dist_vec.at(0);
435  for (int i=1; i < (int)dist_vec.size(); i++)
436  {
437  if (dist_vec.at(i) < last_value)
438  {
439  last_value = dist_vec.at(i);
440  index_min = i;
441  }
442  }
443  if (distance)
444  *distance = last_value;
445  return begin_idx+index_min;
446 }
447 
448 
449 int TimedElasticBand::findClosestTrajectoryPose(const Eigen::Ref<const Eigen::Vector2d>& ref_line_start, const Eigen::Ref<const Eigen::Vector2d>& ref_line_end, double* distance) const
450 {
451  std::vector<double> dist_vec; // TODO: improve! efficiency
452  dist_vec.reserve(sizePoses());
453 
454  int n = sizePoses();
455 
456  // calc distances
457  for (int i = 0; i < n; i++)
458  {
459  Eigen::Vector2d point = Pose(i).position();
460  double diff = distance_point_to_segment_2d(point, ref_line_start, ref_line_end);
461  dist_vec.push_back(diff);
462  }
463 
464  if (dist_vec.empty())
465  return -1;
466 
467  // find minimum
468  int index_min = 0;
469 
470  double last_value = dist_vec.at(0);
471  for (int i=1; i < (int)dist_vec.size(); i++)
472  {
473  if (dist_vec.at(i) < last_value)
474  {
475  last_value = dist_vec.at(i);
476  index_min = i;
477  }
478  }
479  if (distance)
480  *distance = last_value;
481  return index_min; // return index, because it's equal to the vertex, which represents this bandpoint
482 }
483 
485 {
486  if (vertices.empty())
487  return 0;
488  else if (vertices.size() == 1)
489  return findClosestTrajectoryPose(vertices.front());
490  else if (vertices.size() == 2)
491  return findClosestTrajectoryPose(vertices.front(), vertices.back());
492 
493  std::vector<double> dist_vec; // TODO: improve! efficiency
494  dist_vec.reserve(sizePoses());
495 
496  int n = sizePoses();
497 
498  // calc distances
499  for (int i = 0; i < n; i++)
500  {
501  Eigen::Vector2d point = Pose(i).position();
502  double diff = HUGE_VAL;
503  for (int j = 0; j < (int) vertices.size()-1; ++j)
504  {
505  diff = std::min(diff, distance_point_to_segment_2d(point, vertices[j], vertices[j+1]));
506  }
507  diff = std::min(diff, distance_point_to_segment_2d(point, vertices.back(), vertices.front()));
508  dist_vec.push_back(diff);
509  }
510 
511  if (dist_vec.empty())
512  return -1;
513 
514  // find minimum
515  int index_min = 0;
516 
517  double last_value = dist_vec.at(0);
518  for (int i=1; i < (int)dist_vec.size(); i++)
519  {
520  if (dist_vec.at(i) < last_value)
521  {
522  last_value = dist_vec.at(i);
523  index_min = i;
524  }
525  }
526  if (distance)
527  *distance = last_value;
528  return index_min; // return index, because it's equal to the vertex, which represents this bandpoint
529 }
530 
531 
532 int TimedElasticBand::findClosestTrajectoryPose(const Obstacle& obstacle, double* distance) const
533 {
534  const PointObstacle* pobst = dynamic_cast<const PointObstacle*>(&obstacle);
535  if (pobst)
536  return findClosestTrajectoryPose(pobst->position(), distance);
537 
538  const LineObstacle* lobst = dynamic_cast<const LineObstacle*>(&obstacle);
539  if (lobst)
540  return findClosestTrajectoryPose(lobst->start(), lobst->end(), distance);
541 
542  const PolygonObstacle* polyobst = dynamic_cast<const PolygonObstacle*>(&obstacle);
543  if (polyobst)
544  return findClosestTrajectoryPose(polyobst->vertices(), distance);
545 
546  return findClosestTrajectoryPose(obstacle.getCentroid(), distance);
547 }
548 
549 
550 
551 
552 bool TimedElasticBand::detectDetoursBackwards(double threshold) const
553 {
554  if (sizePoses()<2) return false;
555 
556  Eigen::Vector2d d_start_goal = BackPose().position() - Pose(0).position();
557  d_start_goal.normalize(); // using scalar_product without normalizing vectors first result in different threshold-effects
558 
560  for(int i=0; i < sizePoses(); ++i)
561  {
562  Eigen::Vector2d orient_vector(cos( Pose(i).theta() ), sin( Pose(i).theta() ) );
563  if (orient_vector.dot(d_start_goal) < threshold)
564  {
565  ROS_DEBUG("detectDetoursBackwards() - mark TEB for deletion: start-orientation vs startgoal-vec");
566  return true; // backward direction found
567  }
568  }
569 
571  // TODO: maybe we need a small hysteresis?
572 /* for (unsigned int i=0;i<2;++i) // check only a few upcoming
573  {
574  if (i+1 >= sizePoses()) break;
575  Eigen::Vector2d start2conf = Pose(i+1).position() - Pose(0).position();
576  double dist = start2conf.norm();
577  start2conf = start2conf/dist; // normalize -> we don't use start2conf.normalize() since we want to use dist later
578  if (start2conf.dot(d_start_goal) < threshold && dist>0.01) // skip very small displacements
579  {
580  ROS_DEBUG("detectDetoursBackwards() - mark TEB for deletion: curvature look-ahead relative to startconf");
581  return true;
582  }
583  }*/
584  return false;
585 }
586 
587 
588 
589 
590 void TimedElasticBand::updateAndPruneTEB(boost::optional<const PoseSE2&> new_start, boost::optional<const PoseSE2&> new_goal, int min_samples)
591 {
592  // first and simple approach: change only start confs (and virtual start conf for inital velocity)
593  // TEST if optimizer can handle this "hard" placement
594 
595  if (new_start && sizePoses()>0)
596  {
597  // find nearest state (using l2-norm) in order to prune the trajectory
598  // (remove already passed states)
599  double dist_cache = (new_start->position()- Pose(0).position()).norm();
600  double dist;
601  int lookahead = std::min<int>( sizePoses()-min_samples, 10); // satisfy min_samples, otherwise max 10 samples
602 
603  int nearest_idx = 0;
604  for (int i = 1; i<=lookahead; ++i)
605  {
606  dist = (new_start->position()- Pose(i).position()).norm();
607  if (dist<dist_cache)
608  {
609  dist_cache = dist;
610  nearest_idx = i;
611  }
612  else break;
613  }
614 
615  // prune trajectory at the beginning (and extrapolate sequences at the end if the horizon is fixed)
616  if (nearest_idx>0)
617  {
618  // nearest_idx is equal to the number of samples to be removed (since it counts from 0 ;-) )
619  // WARNING delete starting at pose 1, and overwrite the original pose(0) with new_start, since Pose(0) is fixed during optimization!
620  deletePoses(1, nearest_idx); // delete first states such that the closest state is the new first one
621  deleteTimeDiffs(1, nearest_idx); // delete corresponding time differences
622  }
623 
624  // update start
625  Pose(0) = *new_start;
626  }
627 
628  if (new_goal && sizePoses()>0)
629  {
630  BackPose() = *new_goal;
631  }
632 };
633 
634 
635 bool TimedElasticBand::isTrajectoryInsideRegion(double radius, double max_dist_behind_robot, int skip_poses)
636 {
637  if (sizePoses()<=0)
638  return true;
639 
640  double radius_sq = radius*radius;
641  double max_dist_behind_robot_sq = max_dist_behind_robot*max_dist_behind_robot;
642  Eigen::Vector2d robot_orient = Pose(0).orientationUnitVec();
643 
644  for (int i=1; i<sizePoses(); i=i+skip_poses+1)
645  {
646  Eigen::Vector2d dist_vec = Pose(i).position()-Pose(0).position();
647  double dist_sq = dist_vec.squaredNorm();
648 
649  if (dist_sq > radius_sq)
650  {
651  ROS_INFO("outside robot");
652  return false;
653  }
654 
655  // check behind the robot with a different distance, if specified (or >=0)
656  if (max_dist_behind_robot >= 0 && dist_vec.dot(robot_orient) < 0 && dist_sq > max_dist_behind_robot_sq)
657  {
658  ROS_INFO("outside robot behind");
659  return false;
660  }
661 
662  }
663  return true;
664 }
665 
666 
667 
668 
669 } // 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.
bool detectDetoursBackwards(double threshold=0) const
Detect whether the trajectory contains detours.
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...
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
#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) ...
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
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 5 2019 19:25:10