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
00040 #ifndef OBSTACLES_H
00041 #define OBSTACLES_H
00042
00043 #include <Eigen/Core>
00044 #include <Eigen/StdVector>
00045
00046 #include <complex>
00047
00048 #include <boost/shared_ptr.hpp>
00049 #include <boost/pointer_cast.hpp>
00050 #include <geometry_msgs/Polygon.h>
00051 #include <teb_local_planner/distance_calculations.h>
00052
00053
00054 namespace teb_local_planner
00055 {
00056
00061 class Obstacle
00062 {
00063 public:
00064
00068 Obstacle() : dynamic_(false), centroid_velocity_(Eigen::Vector2d::Zero())
00069 {
00070 }
00071
00075 virtual ~Obstacle()
00076 {
00077 }
00078
00079
00082
00087 virtual const Eigen::Vector2d& getCentroid() const = 0;
00088
00093 virtual std::complex<double> getCentroidCplx() const = 0;
00094
00096
00097
00100
00107 virtual bool checkCollision(const Eigen::Vector2d& position, double min_dist) const = 0;
00108
00116 virtual bool checkLineIntersection(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, double min_dist=0) const = 0;
00117
00123 virtual double getMinimumDistance(const Eigen::Vector2d& position) const = 0;
00124
00131 virtual double getMinimumDistance(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end) const = 0;
00132
00138 virtual double getMinimumDistance(const Point2dContainer& polygon) const = 0;
00139
00145 virtual Eigen::Vector2d getClosestPoint(const Eigen::Vector2d& position) const = 0;
00146
00148
00149
00150
00153
00158 bool isDynamic() const {return dynamic_;}
00159
00165 void setCentroidVelocity(const Eigen::Ref<const Eigen::Vector2d>& vel) {centroid_velocity_ = vel; dynamic_=true;}
00166
00171 const Eigen::Vector2d& getCentroidVelocity() const {return centroid_velocity_;}
00172
00174
00175
00176
00179
00188 virtual void toPolygonMsg(geometry_msgs::Polygon& polygon) = 0;
00189
00191
00192 protected:
00193
00194 bool dynamic_;
00195 Eigen::Vector2d centroid_velocity_;
00196
00197 public:
00198 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00199 };
00200
00201
00203 typedef boost::shared_ptr<Obstacle> ObstaclePtr;
00205 typedef boost::shared_ptr<const Obstacle> ObstacleConstPtr;
00207 typedef std::vector<ObstaclePtr> ObstContainer;
00208
00209
00210
00215 class PointObstacle : public Obstacle
00216 {
00217 public:
00218
00222 PointObstacle() : Obstacle(), pos_(Eigen::Vector2d::Zero())
00223 {}
00224
00229 PointObstacle(const Eigen::Ref< const Eigen::Vector2d>& position) : Obstacle(), pos_(position)
00230 {}
00231
00237 PointObstacle(double x, double y) : Obstacle(), pos_(Eigen::Vector2d(x,y))
00238 {}
00239
00240
00241
00242 virtual bool checkCollision(const Eigen::Vector2d& point, double min_dist) const
00243 {
00244 return getMinimumDistance(point) < min_dist;
00245 }
00246
00247
00248
00249 virtual bool checkLineIntersection(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, double min_dist=0) const
00250 {
00251
00252
00253 Eigen::Vector2d a = line_end-line_start;
00254 Eigen::Vector2d b = pos_-line_start;
00255
00256
00257 double t = a.dot(b)/a.dot(a);
00258 if (t<0) t=0;
00259 else if (t>1) t=1;
00260 Eigen::Vector2d nearest_point = line_start + a*t;
00261
00262
00263 return checkCollision(nearest_point, min_dist);
00264 }
00265
00266
00267
00268 virtual double getMinimumDistance(const Eigen::Vector2d& position) const
00269 {
00270 return (position-pos_).norm();
00271 }
00272
00273
00274 virtual double getMinimumDistance(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end) const
00275 {
00276 return distance_point_to_segment_2d(pos_, line_start, line_end);
00277 }
00278
00279
00280 virtual double getMinimumDistance(const Point2dContainer& polygon) const
00281 {
00282 return distance_point_to_polygon_2d(pos_, polygon);
00283 }
00284
00285
00286 virtual Eigen::Vector2d getClosestPoint(const Eigen::Vector2d& position) const
00287 {
00288 return pos_;
00289 }
00290
00291
00292 virtual const Eigen::Vector2d& getCentroid() const
00293 {
00294 return pos_;
00295 }
00296
00297
00298
00299 virtual std::complex<double> getCentroidCplx() const
00300 {
00301 return std::complex<double>(pos_[0],pos_[1]);
00302 }
00303
00304
00305 const Eigen::Vector2d& position() const {return pos_;}
00306 Eigen::Vector2d& position() {return pos_;}
00307 double& x() {return pos_.coeffRef(0);}
00308 const double& x() const {return pos_.coeffRef(0);}
00309 double& y() {return pos_.coeffRef(1);}
00310 const double& y() const {return pos_.coeffRef(1);}
00311
00312
00313 virtual void toPolygonMsg(geometry_msgs::Polygon& polygon)
00314 {
00315 polygon.points.resize(1);
00316 polygon.points.front().x = pos_.x();
00317 polygon.points.front().y = pos_.y();
00318 polygon.points.front().z = 0;
00319 }
00320
00321 protected:
00322
00323 Eigen::Vector2d pos_;
00324
00325
00326 public:
00327 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00328 };
00329
00330
00331
00337 class LineObstacle : public Obstacle
00338 {
00339 public:
00341 typedef std::vector<Eigen::Vector2d,Eigen::aligned_allocator<Eigen::Vector2d> > VertexContainer;
00342
00346 LineObstacle() : Obstacle()
00347 {
00348 start_.setZero();
00349 end_.setZero();
00350 centroid_.setZero();
00351 }
00352
00358 LineObstacle(const Eigen::Ref< const Eigen::Vector2d>& line_start, const Eigen::Ref< const Eigen::Vector2d>& line_end)
00359 : Obstacle(), start_(line_start), end_(line_end)
00360 {
00361 calcCentroid();
00362 }
00363
00371 LineObstacle(double x1, double y1, double x2, double y2) : Obstacle()
00372 {
00373 start_.x() = x1;
00374 start_.y() = y1;
00375 end_.x() = x2;
00376 end_.y() = y2;
00377 calcCentroid();
00378 }
00379
00380
00381 virtual bool checkCollision(const Eigen::Vector2d& point, double min_dist) const
00382 {
00383 return getMinimumDistance(point) <= min_dist;
00384 }
00385
00386
00387 virtual bool checkLineIntersection(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, double min_dist=0) const
00388 {
00389 return check_line_segments_intersection_2d(line_start, line_end, start_, end_);
00390 }
00391
00392
00393 virtual double getMinimumDistance(const Eigen::Vector2d& position) const
00394 {
00395 return distance_point_to_segment_2d(position, start_, end_);
00396 }
00397
00398
00399 virtual double getMinimumDistance(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end) const
00400 {
00401 return distance_segment_to_segment_2d(start_, end_, line_start, line_end);
00402 }
00403
00404
00405 virtual double getMinimumDistance(const Point2dContainer& polygon) const
00406 {
00407 return distance_segment_to_polygon_2d(start_, end_, polygon);
00408 }
00409
00410
00411 virtual Eigen::Vector2d getClosestPoint(const Eigen::Vector2d& position) const
00412 {
00413 return closest_point_on_line_segment_2d(position, start_, end_);
00414 }
00415
00416
00417
00418
00419 virtual const Eigen::Vector2d& getCentroid() const
00420 {
00421 return centroid_;
00422 }
00423
00424
00425 virtual std::complex<double> getCentroidCplx() const
00426 {
00427 return std::complex<double>(centroid_.x(), centroid_.y());
00428 }
00429
00430
00431 const Eigen::Vector2d& start() const {return start_;}
00432 void setStart(const Eigen::Ref<const Eigen::Vector2d>& start) {start_ = start; calcCentroid();}
00433 const Eigen::Vector2d& end() const {return end_;}
00434 void setEnd(const Eigen::Ref<const Eigen::Vector2d>& end) {end_ = end; calcCentroid();}
00435
00436
00437 virtual void toPolygonMsg(geometry_msgs::Polygon& polygon)
00438 {
00439 polygon.points.resize(2);
00440 polygon.points.front().x = start_.x();
00441 polygon.points.front().y = start_.y();
00442
00443 polygon.points.back().x = end_.x();
00444 polygon.points.back().y = end_.y();
00445 polygon.points.back().z = polygon.points.front().z = 0;
00446 }
00447
00448 protected:
00449 void calcCentroid() { centroid_ = 0.5*(start_ + end_); }
00450
00451 private:
00452 Eigen::Vector2d start_;
00453 Eigen::Vector2d end_;
00454
00455 Eigen::Vector2d centroid_;
00456
00457 public:
00458 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00459 };
00460
00461
00469 class PolygonObstacle : public Obstacle
00470 {
00471 public:
00472
00476 PolygonObstacle() : Obstacle(), finalized_(false)
00477 {
00478 centroid_.setConstant(NAN);
00479 }
00480
00481
00482
00483
00484
00485
00486
00487
00488
00489
00490
00491
00492
00493
00494 virtual bool checkCollision(const Eigen::Vector2d& point, double min_dist) const
00495 {
00496
00497 if (noVertices()==2)
00498 return getMinimumDistance(point) <= min_dist;
00499
00500
00501
00502
00503 size_t i, j;
00504 bool c = false;
00505 for (i = 0, j = noVertices()-1; i < noVertices(); j = i++)
00506 {
00507 if ( ((vertices_.at(i).y()>point.y()) != (vertices_.at(j).y()>point.y())) &&
00508 (point.x() < (vertices_.at(j).x()-vertices_.at(i).x()) * (point.y()-vertices_.at(i).y()) / (vertices_.at(j).y()-vertices_.at(i).y()) + vertices_.at(i).x()) )
00509 c = !c;
00510 }
00511 if (c>0) return true;
00512
00513
00514
00515 return min_dist == 0 ? false : getMinimumDistance(point) < min_dist;
00516 }
00517
00518
00527 virtual bool checkLineIntersection(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, double min_dist=0) const;
00528
00529
00530
00531 virtual double getMinimumDistance(const Eigen::Vector2d& position) const
00532 {
00533 return distance_point_to_polygon_2d(position, vertices_);
00534 }
00535
00536
00537 virtual double getMinimumDistance(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end) const
00538 {
00539 return distance_segment_to_polygon_2d(line_start, line_end, vertices_);
00540 }
00541
00542
00543 virtual double getMinimumDistance(const Point2dContainer& polygon) const
00544 {
00545 return distance_polygon_to_polygon_2d(polygon, vertices_);
00546 }
00547
00548
00549 virtual Eigen::Vector2d getClosestPoint(const Eigen::Vector2d& position) const;
00550
00551
00552 virtual const Eigen::Vector2d& getCentroid() const
00553 {
00554 assert(finalized_ && "Finalize the polygon after all vertices are added.");
00555 return centroid_;
00556 }
00557
00558
00559 virtual std::complex<double> getCentroidCplx() const
00560 {
00561 assert(finalized_ && "Finalize the polygon after all vertices are added.");
00562 return std::complex<double>(centroid_.coeffRef(0), centroid_.coeffRef(1));
00563 }
00564
00565
00566 virtual void toPolygonMsg(geometry_msgs::Polygon& polygon);
00567
00568
00570
00571
00572
00573 const Point2dContainer& vertices() const {return vertices_;}
00574 Point2dContainer& vertices() {return vertices_;}
00575
00582 void pushBackVertex(const Eigen::Ref<const Eigen::Vector2d>& vertex)
00583 {
00584 vertices_.push_back(vertex);
00585 finalized_ = false;
00586 }
00587
00595 void pushBackVertex(double x, double y)
00596 {
00597 vertices_.push_back(Eigen::Vector2d(x,y));
00598 finalized_ = false;
00599 }
00600
00604 void finalizePolygon()
00605 {
00606 fixPolygonClosure();
00607 calcCentroid();
00608 finalized_ = true;
00609 }
00610
00614 void clearVertices() {vertices_.clear(); finalized_ = false;}
00615
00619 size_t noVertices() const {return vertices_.size();}
00620
00621
00623
00624 protected:
00625
00626 void fixPolygonClosure();
00627
00628 void calcCentroid();
00629
00630
00631 Point2dContainer vertices_;
00632 Eigen::Vector2d centroid_;
00633
00634 bool finalized_;
00635
00636
00637
00638 public:
00639 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00640 };
00641
00642
00643 }
00644
00645 #endif