Go to the documentation of this file.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 ROBOT_FOOTPRINT_MODEL_H
00041 #define ROBOT_FOOTPRINT_MODEL_H
00042
00043 #include <teb_local_planner/pose_se2.h>
00044 #include <teb_local_planner/obstacles.h>
00045 #include <visualization_msgs/Marker.h>
00046
00047 namespace teb_local_planner
00048 {
00049
00058 class BaseRobotFootprintModel
00059 {
00060 public:
00061
00065 BaseRobotFootprintModel()
00066 {
00067 }
00068
00072 virtual ~BaseRobotFootprintModel()
00073 {
00074 }
00075
00076
00083 virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const = 0;
00084
00093 virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers ) const {}
00094
00095
00100 virtual double getInscribedRadius() = 0;
00101
00102
00103
00104 public:
00105 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00106 };
00107
00108
00110 typedef boost::shared_ptr<BaseRobotFootprintModel> RobotFootprintModelPtr;
00112 typedef boost::shared_ptr<const BaseRobotFootprintModel> RobotFootprintModelConstPtr;
00113
00114
00115
00124 class PointRobotFootprint : public BaseRobotFootprintModel
00125 {
00126 public:
00127
00131 PointRobotFootprint() {}
00132
00136 virtual ~PointRobotFootprint() {}
00137
00144 virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
00145 {
00146 return obstacle->getMinimumDistance(current_pose.position());
00147 }
00148
00153 virtual double getInscribedRadius() {return 0.0;}
00154
00155 };
00156
00157
00162 class CircularRobotFootprint : public BaseRobotFootprintModel
00163 {
00164 public:
00165
00170 CircularRobotFootprint(double radius) : radius_(radius) { }
00171
00175 virtual ~CircularRobotFootprint() { }
00176
00181 void setRadius(double radius) {radius_ = radius;}
00182
00189 virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
00190 {
00191 return obstacle->getMinimumDistance(current_pose.position()) - radius_;
00192 }
00193
00202 virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers ) const
00203 {
00204 markers.resize(1);
00205 visualization_msgs::Marker& marker = markers.back();
00206 marker.type = visualization_msgs::Marker::CYLINDER;
00207 current_pose.toPoseMsg(marker.pose);
00208 marker.scale.x = marker.scale.y = 2*radius_;
00209 marker.scale.z = 0.05;
00210 marker.color.a = 0.5;
00211 marker.color.r = 0.0;
00212 marker.color.g = 0.8;
00213 marker.color.b = 0.0;
00214 }
00215
00220 virtual double getInscribedRadius() {return radius_;}
00221
00222 private:
00223
00224 double radius_;
00225 };
00226
00227
00232 class TwoCirclesRobotFootprint : public BaseRobotFootprintModel
00233 {
00234 public:
00235
00243 TwoCirclesRobotFootprint(double front_offset, double front_radius, double rear_offset, double rear_radius)
00244 : front_offset_(front_offset), front_radius_(front_radius), rear_offset_(rear_offset), rear_radius_(rear_radius) { }
00245
00249 virtual ~TwoCirclesRobotFootprint() { }
00250
00258 void setParameters(double front_offset, double front_radius, double rear_offset, double rear_radius)
00259 {front_offset_=front_offset; front_radius_=front_radius; rear_offset_=rear_offset; rear_radius_=rear_radius;}
00260
00267 virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
00268 {
00269 Eigen::Vector2d dir = current_pose.orientationUnitVec();
00270 double dist_front = obstacle->getMinimumDistance(current_pose.position() + front_offset_*dir) - front_radius_;
00271 double dist_rear = obstacle->getMinimumDistance(current_pose.position() - rear_offset_*dir) - rear_radius_;
00272 return std::min(dist_front, dist_rear);
00273 }
00274
00283 virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers ) const
00284 {
00285 std_msgs::ColorRGBA color;
00286 color.a = 0.5;
00287 color.r = 0.0;
00288 color.g = 0.8;
00289 color.b = 0.0;
00290
00291 Eigen::Vector2d dir = current_pose.orientationUnitVec();
00292 if (front_radius_>0)
00293 {
00294 markers.push_back(visualization_msgs::Marker());
00295 visualization_msgs::Marker& marker1 = markers.front();
00296 marker1.type = visualization_msgs::Marker::CYLINDER;
00297 current_pose.toPoseMsg(marker1.pose);
00298 marker1.pose.position.x += front_offset_*dir.x();
00299 marker1.pose.position.y += front_offset_*dir.y();
00300 marker1.scale.x = marker1.scale.y = 2*front_radius_;
00301
00302 marker1.color = color;
00303
00304 }
00305 if (rear_radius_>0)
00306 {
00307 markers.push_back(visualization_msgs::Marker());
00308 visualization_msgs::Marker& marker2 = markers.back();
00309 marker2.type = visualization_msgs::Marker::CYLINDER;
00310 current_pose.toPoseMsg(marker2.pose);
00311 marker2.pose.position.x -= rear_offset_*dir.x();
00312 marker2.pose.position.y -= rear_offset_*dir.y();
00313 marker2.scale.x = marker2.scale.y = 2*rear_radius_;
00314
00315 marker2.color = color;
00316 }
00317 }
00318
00323 virtual double getInscribedRadius()
00324 {
00325 double min_longitudinal = std::min(rear_offset_ + rear_radius_, front_offset_ + front_radius_);
00326 double min_lateral = std::min(rear_radius_, front_radius_);
00327 return std::min(min_longitudinal, min_lateral);
00328 }
00329
00330 private:
00331
00332 double front_offset_;
00333 double front_radius_;
00334 double rear_offset_;
00335 double rear_radius_;
00336
00337 };
00338
00339
00340
00345 class LineRobotFootprint : public BaseRobotFootprintModel
00346 {
00347 public:
00348
00354 LineRobotFootprint(const geometry_msgs::Point& line_start, const geometry_msgs::Point& line_end)
00355 {
00356 setLine(line_start, line_end);
00357 }
00358
00364 LineRobotFootprint(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end)
00365 {
00366 setLine(line_start, line_end);
00367 }
00368
00372 virtual ~LineRobotFootprint() { }
00373
00378 void setLine(const geometry_msgs::Point& line_start, const geometry_msgs::Point& line_end)
00379 {
00380 line_start_.x() = line_start.x;
00381 line_start_.y() = line_start.y;
00382 line_end_.x() = line_end.x;
00383 line_end_.y() = line_end.y;
00384 }
00385
00390 void setLine(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end)
00391 {
00392 line_start_ = line_start;
00393 line_end_ = line_end;
00394 }
00395
00402 virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
00403 {
00404
00405 double cos_th = std::cos(current_pose.theta());
00406 double sin_th = std::sin(current_pose.theta());
00407 Eigen::Vector2d line_start_world;
00408 line_start_world.x() = current_pose.x() + cos_th * line_start_.x() - sin_th * line_start_.y();
00409 line_start_world.y() = current_pose.y() + sin_th * line_start_.x() + cos_th * line_start_.y();
00410 Eigen::Vector2d line_end_world;
00411 line_end_world.x() = current_pose.x() + cos_th * line_end_.x() - sin_th * line_end_.y();
00412 line_end_world.y() = current_pose.y() + sin_th * line_end_.x() + cos_th * line_end_.y();
00413 return obstacle->getMinimumDistance(line_start_world, line_end_world);
00414 }
00415
00424 virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers ) const
00425 {
00426 std_msgs::ColorRGBA color;
00427 color.a = 0.5;
00428 color.r = 0.0;
00429 color.g = 0.8;
00430 color.b = 0.0;
00431
00432 markers.push_back(visualization_msgs::Marker());
00433 visualization_msgs::Marker& marker = markers.front();
00434 marker.type = visualization_msgs::Marker::LINE_STRIP;
00435 current_pose.toPoseMsg(marker.pose);
00436
00437
00438 geometry_msgs::Point line_start_world;
00439 line_start_world.x = line_start_.x();
00440 line_start_world.y = line_start_.y();
00441 line_start_world.z = 0;
00442 marker.points.push_back(line_start_world);
00443
00444 geometry_msgs::Point line_end_world;
00445 line_end_world.x = line_end_.x();
00446 line_end_world.y = line_end_.y();
00447 line_end_world.z = 0;
00448 marker.points.push_back(line_end_world);
00449
00450 marker.scale.x = 0.05;
00451 marker.color = color;
00452 }
00453
00458 virtual double getInscribedRadius()
00459 {
00460 return 0.0;
00461 }
00462
00463 private:
00464
00465 Eigen::Vector2d line_start_;
00466 Eigen::Vector2d line_end_;
00467
00468 public:
00469 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00470
00471 };
00472
00473
00474
00479 class PolygonRobotFootprint : public BaseRobotFootprintModel
00480 {
00481 public:
00482
00483
00484
00489 PolygonRobotFootprint(const Point2dContainer& vertices) : vertices_(vertices) { }
00490
00494 virtual ~PolygonRobotFootprint() { }
00495
00500 void setVertices(const Point2dContainer& vertices) {vertices_ = vertices;}
00501
00508 virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
00509 {
00510
00511 double cos_th = std::cos(current_pose.theta());
00512 double sin_th = std::sin(current_pose.theta());
00513 Point2dContainer polygon_world(vertices_.size());
00514 for (std::size_t i=0; i<vertices_.size(); ++i)
00515 {
00516 polygon_world[i].x() = current_pose.x() + cos_th * vertices_[i].x() - sin_th * vertices_[i].y();
00517 polygon_world[i].y() = current_pose.y() + sin_th * vertices_[i].x() + cos_th * vertices_[i].y();
00518 }
00519 return obstacle->getMinimumDistance(polygon_world);
00520 }
00521
00530 virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers ) const
00531 {
00532 if (vertices_.empty())
00533 return;
00534
00535 std_msgs::ColorRGBA color;
00536 color.a = 0.5;
00537 color.r = 0.0;
00538 color.g = 0.8;
00539 color.b = 0.0;
00540
00541 markers.push_back(visualization_msgs::Marker());
00542 visualization_msgs::Marker& marker = markers.front();
00543 marker.type = visualization_msgs::Marker::LINE_STRIP;
00544 current_pose.toPoseMsg(marker.pose);
00545
00546 for (std::size_t i = 0; i < vertices_.size(); ++i)
00547 {
00548 geometry_msgs::Point point;
00549 point.x = vertices_[i].x();
00550 point.y = vertices_[i].y();
00551 point.z = 0;
00552 marker.points.push_back(point);
00553 }
00554
00555 geometry_msgs::Point point;
00556 point.x = vertices_.front().x();
00557 point.y = vertices_.front().y();
00558 point.z = 0;
00559 marker.points.push_back(point);
00560
00561 marker.scale.x = 0.025;
00562 marker.color = color;
00563
00564 }
00565
00570 virtual double getInscribedRadius()
00571 {
00572 double min_dist = std::numeric_limits<double>::max();
00573 Eigen::Vector2d center(0.0, 0.0);
00574
00575 if (vertices_.size() <= 2)
00576 return 0.0;
00577
00578 for (int i = 0; i < (int)vertices_.size() - 1; ++i)
00579 {
00580
00581 double vertex_dist = vertices_[i].norm();
00582 double edge_dist = distance_point_to_segment_2d(center, vertices_[i], vertices_[i+1]);
00583 min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
00584 }
00585
00586
00587 double vertex_dist = vertices_.back().norm();
00588 double edge_dist = distance_point_to_segment_2d(center, vertices_.back(), vertices_.front());
00589 return std::min(min_dist, std::min(vertex_dist, edge_dist));
00590 }
00591
00592 private:
00593
00594 Point2dContainer vertices_;
00595
00596 };
00597
00598
00599
00600
00601
00602 }
00603
00604 #endif