00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #include <teb_local_planner/timed_elastic_band.h>
00040
00041
00042 namespace teb_local_planner
00043 {
00044
00045
00046 TimedElasticBand::TimedElasticBand()
00047 {
00048 }
00049
00050 TimedElasticBand::~TimedElasticBand()
00051 {
00052 ROS_DEBUG("Destructor Timed_Elastic_Band...");
00053 clearTimedElasticBand();
00054 }
00055
00056
00057 void TimedElasticBand::addPose(const PoseSE2& pose, bool fixed)
00058 {
00059 VertexPose* pose_vertex = new VertexPose(pose, fixed);
00060 pose_vec_.push_back( pose_vertex );
00061 return;
00062 }
00063
00064 void TimedElasticBand::addPose(const Eigen::Ref<const Eigen::Vector2d>& position, double theta, bool fixed)
00065 {
00066 VertexPose* pose_vertex = new VertexPose(position, theta, fixed);
00067 pose_vec_.push_back( pose_vertex );
00068 return;
00069 }
00070
00071 void TimedElasticBand::addPose(double x, double y, double theta, bool fixed)
00072 {
00073 VertexPose* pose_vertex = new VertexPose(x, y, theta, fixed);
00074 pose_vec_.push_back( pose_vertex );
00075 return;
00076 }
00077
00078 void TimedElasticBand::addTimeDiff(double dt, bool fixed)
00079 {
00080 VertexTimeDiff* timediff_vertex = new VertexTimeDiff(dt, fixed);
00081 timediff_vec_.push_back( timediff_vertex );
00082 return;
00083 }
00084
00085
00086 void TimedElasticBand::addPoseAndTimeDiff(double x, double y, double angle, double dt)
00087 {
00088 if (sizePoses() != sizeTimeDiffs())
00089 {
00090 addPose(x,y,angle,false);
00091 addTimeDiff(dt,false);
00092 }
00093 else
00094 ROS_ERROR("Method addPoseAndTimeDiff: Add one single Pose first. Timediff describes the time difference between last conf and given conf");
00095 return;
00096 }
00097
00098
00099
00100 void TimedElasticBand::addPoseAndTimeDiff(const PoseSE2& pose, double dt)
00101 {
00102 if (sizePoses() != sizeTimeDiffs())
00103 {
00104 addPose(pose,false);
00105 addTimeDiff(dt,false);
00106 } else
00107 ROS_ERROR("Method addPoseAndTimeDiff: Add one single Pose first. Timediff describes the time difference between last conf and given conf");
00108 return;
00109 }
00110
00111 void TimedElasticBand::addPoseAndTimeDiff(const Eigen::Ref<const Eigen::Vector2d>& position, double theta, double dt)
00112 {
00113 if (sizePoses() != sizeTimeDiffs())
00114 {
00115 addPose(position, theta,false);
00116 addTimeDiff(dt,false);
00117 } else
00118 ROS_ERROR("Method addPoseAndTimeDiff: Add one single Pose first. Timediff describes the time difference between last conf and given conf");
00119 return;
00120 }
00121
00122
00123 void TimedElasticBand::deletePose(int index)
00124 {
00125 ROS_ASSERT(index<pose_vec_.size());
00126 delete pose_vec_.at(index);
00127 pose_vec_.erase(pose_vec_.begin()+index);
00128 }
00129
00130 void TimedElasticBand::deletePoses(int index, int number)
00131 {
00132 ROS_ASSERT(index+number<=(int)pose_vec_.size());
00133 for (int i = index; i<index+number; ++i)
00134 delete pose_vec_.at(i);
00135 pose_vec_.erase(pose_vec_.begin()+index, pose_vec_.begin()+index+number);
00136 }
00137
00138 void TimedElasticBand::deleteTimeDiff(int index)
00139 {
00140 ROS_ASSERT(index<(int)timediff_vec_.size());
00141 delete timediff_vec_.at(index);
00142 timediff_vec_.erase(timediff_vec_.begin()+index);
00143 }
00144
00145 void TimedElasticBand::deleteTimeDiffs(int index, int number)
00146 {
00147 ROS_ASSERT(index+number<=timediff_vec_.size());
00148 for (int i = index; i<index+number; ++i)
00149 delete timediff_vec_.at(i);
00150 timediff_vec_.erase(timediff_vec_.begin()+index, timediff_vec_.begin()+index+number);
00151 }
00152
00153 void TimedElasticBand::insertPose(int index, const PoseSE2& pose)
00154 {
00155 VertexPose* pose_vertex = new VertexPose(pose);
00156 pose_vec_.insert(pose_vec_.begin()+index, pose_vertex);
00157 }
00158
00159 void TimedElasticBand::insertPose(int index, const Eigen::Ref<const Eigen::Vector2d>& position, double theta)
00160 {
00161 VertexPose* pose_vertex = new VertexPose(position, theta);
00162 pose_vec_.insert(pose_vec_.begin()+index, pose_vertex);
00163 }
00164
00165 void TimedElasticBand::insertPose(int index, double x, double y, double theta)
00166 {
00167 VertexPose* pose_vertex = new VertexPose(x, y, theta);
00168 pose_vec_.insert(pose_vec_.begin()+index, pose_vertex);
00169 }
00170
00171 void TimedElasticBand::insertTimeDiff(int index, double dt)
00172 {
00173 VertexTimeDiff* timediff_vertex = new VertexTimeDiff(dt);
00174 timediff_vec_.insert(timediff_vec_.begin()+index, timediff_vertex);
00175 }
00176
00177
00178 void TimedElasticBand::clearTimedElasticBand()
00179 {
00180 for (PoseSequence::iterator pose_it = pose_vec_.begin(); pose_it != pose_vec_.end(); ++pose_it)
00181 delete *pose_it;
00182 pose_vec_.clear();
00183
00184 for (TimeDiffSequence::iterator dt_it = timediff_vec_.begin(); dt_it != timediff_vec_.end(); ++dt_it)
00185 delete *dt_it;
00186 timediff_vec_.clear();
00187 }
00188
00189
00190 void TimedElasticBand::setPoseVertexFixed(int index, bool status)
00191 {
00192 ROS_ASSERT(index<sizePoses());
00193 pose_vec_.at(index)->setFixed(status);
00194 }
00195
00196 void TimedElasticBand::setTimeDiffVertexFixed(int index, bool status)
00197 {
00198 ROS_ASSERT(index<sizeTimeDiffs());
00199 timediff_vec_.at(index)->setFixed(status);
00200 }
00201
00202
00203 void TimedElasticBand::autoResize(double dt_ref, double dt_hysteresis, int min_samples, int max_samples)
00204 {
00206 for(int i=0; i < sizeTimeDiffs(); ++i)
00207 {
00208 if(TimeDiff(i) > dt_ref + dt_hysteresis && sizeTimeDiffs()<max_samples)
00209 {
00210
00211
00212 double newtime = 0.5*TimeDiff(i);
00213
00214 TimeDiff(i) = newtime;
00215 insertPose(i+1, PoseSE2::average(Pose(i),Pose(i+1)) );
00216 insertTimeDiff(i+1,newtime);
00217
00218 ++i;
00219 }
00220 else if(TimeDiff(i) < dt_ref - dt_hysteresis && sizeTimeDiffs()>min_samples)
00221 {
00222
00223
00224 if(i < ((int)sizeTimeDiffs()-1))
00225 {
00226 TimeDiff(i+1) = TimeDiff(i+1) + TimeDiff(i);
00227 deleteTimeDiff(i);
00228 deletePose(i+1);
00229 }
00230 }
00231 }
00232 }
00233
00234
00235 double TimedElasticBand::getSumOfAllTimeDiffs() const
00236 {
00237 double time = 0;
00238
00239 for(TimeDiffSequence::const_iterator dt_it = timediff_vec_.begin(); dt_it != timediff_vec_.end(); ++dt_it)
00240 {
00241 time += (*dt_it)->dt();
00242 }
00243 return time;
00244 }
00245
00246 double TimedElasticBand::getAccumulatedDistance() const
00247 {
00248 double dist = 0;
00249
00250 for(int i=1; i<sizePoses(); ++i)
00251 {
00252 dist += (Pose(i).position() - Pose(i-1).position()).norm();
00253 }
00254 return dist;
00255 }
00256
00257 bool TimedElasticBand::initTEBtoGoal(const PoseSE2& start, const PoseSE2& goal, double diststep, double timestep, int min_samples, bool guess_backwards_motion)
00258 {
00259 if (!isInit())
00260 {
00261 addPose(start);
00262 setPoseVertexFixed(0,true);
00263
00264 if (diststep!=0)
00265 {
00266 Eigen::Vector2d point_to_goal = goal.position()-start.position();
00267 double dir_to_goal = std::atan2(point_to_goal[1],point_to_goal[0]);
00268 double dx = diststep*std::cos(dir_to_goal);
00269 double dy = diststep*std::sin(dir_to_goal);
00270 double orient_init = dir_to_goal;
00271
00272 if (guess_backwards_motion && point_to_goal.dot(start.orientationUnitVec()) < 0)
00273 orient_init = g2o::normalize_theta(orient_init+M_PI);
00274
00275 double dist_to_goal = point_to_goal.norm();
00276 double no_steps_d = dist_to_goal/std::abs(diststep);
00277 unsigned int no_steps = (unsigned int) std::floor(no_steps_d);
00278
00279 for (unsigned int i=1; i<=no_steps; i++)
00280 {
00281 if (i==no_steps && no_steps_d==(float) no_steps)
00282 break;
00283 addPoseAndTimeDiff(start.x()+i*dx,start.y()+i*dy,orient_init,timestep);
00284 }
00285
00286 }
00287
00288
00289 if ( sizePoses() < min_samples-1 )
00290 {
00291 ROS_DEBUG("initTEBtoGoal(): number of generated samples is less than specified by min_samples. Forcing the insertion of more samples...");
00292 while (sizePoses() < min_samples-1)
00293 {
00294
00295 addPoseAndTimeDiff( PoseSE2::average(BackPose(), goal), timestep );
00296 }
00297 }
00298
00299
00300 addPoseAndTimeDiff(goal,timestep);
00301 setPoseVertexFixed(sizePoses()-1,true);
00302 }
00303 else
00304 {
00305 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)!");
00306 ROS_WARN("Number of TEB configurations: %d, Number of TEB timediffs: %d",(unsigned int) sizePoses(),(unsigned int) sizeTimeDiffs());
00307 return false;
00308 }
00309 return true;
00310 }
00311
00312
00313 bool TimedElasticBand::initTEBtoGoal(const std::vector<geometry_msgs::PoseStamped>& plan, double dt, bool estimate_orient, int min_samples, bool guess_backwards_motion)
00314 {
00315
00316 if (!isInit())
00317 {
00318 PoseSE2 start(plan.front().pose);
00319 PoseSE2 goal(plan.back().pose);
00320
00321 addPose(start);
00322 setPoseVertexFixed(0,true);
00323
00324 bool backwards = false;
00325 if (guess_backwards_motion && (goal.position()-start.position()).dot(start.orientationUnitVec()) < 0)
00326 backwards = true;
00327
00328
00329 for (int i=1; i<(int)plan.size()-1; ++i)
00330 {
00331 double yaw;
00332 if (estimate_orient)
00333 {
00334
00335 double dx = plan[i+1].pose.position.x - plan[i].pose.position.x;
00336 double dy = plan[i+1].pose.position.y - plan[i].pose.position.y;
00337 yaw = std::atan2(dy,dx);
00338 if (backwards)
00339 yaw = g2o::normalize_theta(yaw+M_PI);
00340 }
00341 else
00342 {
00343 yaw = tf::getYaw(plan[i].pose.orientation);
00344 }
00345 addPoseAndTimeDiff(plan[i].pose.position.x, plan[i].pose.position.y, yaw, dt);
00346 }
00347
00348
00349 if ( sizePoses() < min_samples-1 )
00350 {
00351 ROS_DEBUG("initTEBtoGoal(): number of generated samples is less than specified by min_samples. Forcing the insertion of more samples...");
00352 while (sizePoses() < min_samples-1)
00353 {
00354
00355 addPoseAndTimeDiff( PoseSE2::average(BackPose(), goal), dt );
00356 }
00357 }
00358
00359
00360 addPoseAndTimeDiff(goal, dt);
00361 setPoseVertexFixed(sizePoses()-1,true);
00362 }
00363 else
00364 {
00365 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)!");
00366 ROS_WARN("Number of TEB configurations: %d, Number of TEB timediffs: %d", sizePoses(), sizeTimeDiffs());
00367 return false;
00368 }
00369
00370 return true;
00371 }
00372
00373
00374 int TimedElasticBand::findClosestTrajectoryPose(const Eigen::Ref<const Eigen::Vector2d>& ref_point, double* distance, int begin_idx) const
00375 {
00376 std::vector<double> dist_vec;
00377 dist_vec.reserve(sizePoses());
00378
00379 int n = sizePoses();
00380
00381
00382 for (int i = begin_idx; i < n; i++)
00383 {
00384 Eigen::Vector2d diff = ref_point - Pose(i).position();
00385 dist_vec.push_back(diff.norm());
00386 }
00387
00388 if (dist_vec.empty())
00389 return -1;
00390
00391
00392 int index_min = 0;
00393
00394 double last_value = dist_vec.at(0);
00395 for (int i=1; i < (int)dist_vec.size(); i++)
00396 {
00397 if (dist_vec.at(i) < last_value)
00398 {
00399 last_value = dist_vec.at(i);
00400 index_min = i;
00401 }
00402 }
00403 if (distance)
00404 *distance = last_value;
00405 return begin_idx+index_min;
00406 }
00407
00408
00409 int TimedElasticBand::findClosestTrajectoryPose(const Eigen::Ref<const Eigen::Vector2d>& ref_line_start, const Eigen::Ref<const Eigen::Vector2d>& ref_line_end, double* distance) const
00410 {
00411 std::vector<double> dist_vec;
00412 dist_vec.reserve(sizePoses());
00413
00414 int n = sizePoses();
00415
00416
00417 for (int i = 0; i < n; i++)
00418 {
00419 Eigen::Vector2d point = Pose(i).position();
00420 double diff = distance_point_to_segment_2d(point, ref_line_start, ref_line_end);
00421 dist_vec.push_back(diff);
00422 }
00423
00424 if (dist_vec.empty())
00425 return -1;
00426
00427
00428 int index_min = 0;
00429
00430 double last_value = dist_vec.at(0);
00431 for (int i=1; i < (int)dist_vec.size(); i++)
00432 {
00433 if (dist_vec.at(i) < last_value)
00434 {
00435 last_value = dist_vec.at(i);
00436 index_min = i;
00437 }
00438 }
00439 if (distance)
00440 *distance = last_value;
00441 return index_min;
00442 }
00443
00444 int TimedElasticBand::findClosestTrajectoryPose(const Point2dContainer& vertices, double* distance) const
00445 {
00446 if (vertices.empty())
00447 return 0;
00448 else if (vertices.size() == 1)
00449 return findClosestTrajectoryPose(vertices.front());
00450 else if (vertices.size() == 2)
00451 return findClosestTrajectoryPose(vertices.front(), vertices.back());
00452
00453 std::vector<double> dist_vec;
00454 dist_vec.reserve(sizePoses());
00455
00456 int n = sizePoses();
00457
00458
00459 for (int i = 0; i < n; i++)
00460 {
00461 Eigen::Vector2d point = Pose(i).position();
00462 double diff = HUGE_VAL;
00463 for (int j = 0; j < (int) vertices.size()-1; ++j)
00464 {
00465 diff = std::min(diff, distance_point_to_segment_2d(point, vertices[j], vertices[j+1]));
00466 }
00467 diff = std::min(diff, distance_point_to_segment_2d(point, vertices.back(), vertices.front()));
00468 dist_vec.push_back(diff);
00469 }
00470
00471 if (dist_vec.empty())
00472 return -1;
00473
00474
00475 int index_min = 0;
00476
00477 double last_value = dist_vec.at(0);
00478 for (int i=1; i < (int)dist_vec.size(); i++)
00479 {
00480 if (dist_vec.at(i) < last_value)
00481 {
00482 last_value = dist_vec.at(i);
00483 index_min = i;
00484 }
00485 }
00486 if (distance)
00487 *distance = last_value;
00488 return index_min;
00489 }
00490
00491
00492 int TimedElasticBand::findClosestTrajectoryPose(const Obstacle& obstacle, double* distance) const
00493 {
00494 const PointObstacle* pobst = dynamic_cast<const PointObstacle*>(&obstacle);
00495 if (pobst)
00496 return findClosestTrajectoryPose(pobst->position(), distance);
00497
00498 const LineObstacle* lobst = dynamic_cast<const LineObstacle*>(&obstacle);
00499 if (lobst)
00500 return findClosestTrajectoryPose(lobst->start(), lobst->end(), distance);
00501
00502 const PolygonObstacle* polyobst = dynamic_cast<const PolygonObstacle*>(&obstacle);
00503 if (polyobst)
00504 return findClosestTrajectoryPose(polyobst->vertices(), distance);
00505
00506 return findClosestTrajectoryPose(obstacle.getCentroid(), distance);
00507 }
00508
00509
00510
00511
00512 bool TimedElasticBand::detectDetoursBackwards(double threshold) const
00513 {
00514 if (sizePoses()<2) return false;
00515
00516 Eigen::Vector2d d_start_goal = BackPose().position() - Pose(0).position();
00517 d_start_goal.normalize();
00518
00520 for(int i=0; i < sizePoses(); ++i)
00521 {
00522 Eigen::Vector2d orient_vector(cos( Pose(i).theta() ), sin( Pose(i).theta() ) );
00523 if (orient_vector.dot(d_start_goal) < threshold)
00524 {
00525 ROS_DEBUG("detectDetoursBackwards() - mark TEB for deletion: start-orientation vs startgoal-vec");
00526 return true;
00527 }
00528 }
00529
00531
00532
00533
00534
00535
00536
00537
00538
00539
00540
00541
00542
00543
00544 return false;
00545 }
00546
00547
00548
00549
00550 void TimedElasticBand::updateAndPruneTEB(boost::optional<const PoseSE2&> new_start, boost::optional<const PoseSE2&> new_goal, int min_samples)
00551 {
00552
00553
00554
00555 if (new_start && sizePoses()>0)
00556 {
00557
00558
00559 double dist_cache = (new_start->position()- Pose(0).position()).norm();
00560 double dist;
00561 int lookahead = std::min<int>( sizePoses()-min_samples, 10);
00562
00563 int nearest_idx = 0;
00564 for (int i = 1; i<=lookahead; ++i)
00565 {
00566 dist = (new_start->position()- Pose(i).position()).norm();
00567 if (dist<dist_cache)
00568 {
00569 dist_cache = dist;
00570 nearest_idx = i;
00571 }
00572 else break;
00573 }
00574
00575
00576 if (nearest_idx>0)
00577 {
00578
00579
00580 deletePoses(1, nearest_idx);
00581 deleteTimeDiffs(1, nearest_idx);
00582 }
00583
00584
00585 Pose(0) = *new_start;
00586 }
00587
00588 if (new_goal && sizePoses()>0)
00589 {
00590 BackPose() = *new_goal;
00591 }
00592 };
00593
00594
00595 bool TimedElasticBand::isTrajectoryInsideRegion(double radius, double max_dist_behind_robot, int skip_poses)
00596 {
00597 if (sizePoses()<=0)
00598 return true;
00599
00600 double radius_sq = radius*radius;
00601 double max_dist_behind_robot_sq = max_dist_behind_robot*max_dist_behind_robot;
00602 Eigen::Vector2d robot_orient = Pose(0).orientationUnitVec();
00603
00604 for (int i=1; i<sizePoses(); i=i+skip_poses+1)
00605 {
00606 Eigen::Vector2d dist_vec = Pose(i).position()-Pose(0).position();
00607 double dist_sq = dist_vec.squaredNorm();
00608
00609 if (dist_sq > radius_sq)
00610 {
00611 ROS_INFO("outside robot");
00612 return false;
00613 }
00614
00615
00616 if (max_dist_behind_robot >= 0 && dist_vec.dot(robot_orient) < 0 && dist_sq > max_dist_behind_robot_sq)
00617 {
00618 ROS_INFO("outside robot behind");
00619 return false;
00620 }
00621
00622 }
00623 return true;
00624 }
00625
00626
00627
00628
00629 }