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
00096
00097 public:
00098 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00099 };
00100
00101
00103 typedef boost::shared_ptr<BaseRobotFootprintModel> RobotFootprintModelPtr;
00105 typedef boost::shared_ptr<const BaseRobotFootprintModel> RobotFootprintModelConstPtr;
00106
00107
00108
00117 class PointRobotFootprint : public BaseRobotFootprintModel
00118 {
00119 public:
00120
00124 PointRobotFootprint() {}
00125
00129 virtual ~PointRobotFootprint() {}
00130
00137 virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
00138 {
00139 return obstacle->getMinimumDistance(current_pose.position());
00140 }
00141
00142 };
00143
00144
00149 class CircularRobotFootprint : public BaseRobotFootprintModel
00150 {
00151 public:
00152
00157 CircularRobotFootprint(double radius) : radius_(radius) { }
00158
00162 virtual ~CircularRobotFootprint() { }
00163
00168 void setRadius(double radius) {radius_ = radius;}
00169
00176 virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
00177 {
00178 return obstacle->getMinimumDistance(current_pose.position()) - radius_;
00179 }
00180
00189 virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers ) const
00190 {
00191 markers.resize(1);
00192 visualization_msgs::Marker& marker = markers.back();
00193 marker.type = visualization_msgs::Marker::CYLINDER;
00194 current_pose.toPoseMsg(marker.pose);
00195 marker.scale.x = marker.scale.y = 2*radius_;
00196 marker.scale.z = 0.05;
00197 marker.color.a = 0.5;
00198 marker.color.r = 0.0;
00199 marker.color.g = 0.8;
00200 marker.color.b = 0.0;
00201 }
00202
00203 private:
00204
00205 double radius_;
00206 };
00207
00208
00213 class TwoCirclesRobotFootprint : public BaseRobotFootprintModel
00214 {
00215 public:
00216
00224 TwoCirclesRobotFootprint(double front_offset, double front_radius, double rear_offset, double rear_radius)
00225 : front_offset_(front_offset), front_radius_(front_radius), rear_offset_(rear_offset), rear_radius_(rear_radius) { }
00226
00230 virtual ~TwoCirclesRobotFootprint() { }
00231
00239 void setParameters(double front_offset, double front_radius, double rear_offset, double rear_radius)
00240 {front_offset_=front_offset; front_radius_=front_radius; rear_offset_=rear_offset; rear_radius_=rear_radius;}
00241
00248 virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
00249 {
00250 Eigen::Vector2d dir = current_pose.orientationUnitVec();
00251 double dist_front = obstacle->getMinimumDistance(current_pose.position() + front_offset_*dir) - front_radius_;
00252 double dist_rear = obstacle->getMinimumDistance(current_pose.position() - rear_offset_*dir) - rear_radius_;
00253 return std::min(dist_front, dist_rear);
00254 }
00255
00264 virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers ) const
00265 {
00266 std_msgs::ColorRGBA color;
00267 color.a = 0.5;
00268 color.r = 0.0;
00269 color.g = 0.8;
00270 color.b = 0.0;
00271
00272 Eigen::Vector2d dir = current_pose.orientationUnitVec();
00273 if (front_radius_>0)
00274 {
00275 markers.push_back(visualization_msgs::Marker());
00276 visualization_msgs::Marker& marker1 = markers.front();
00277 marker1.type = visualization_msgs::Marker::CYLINDER;
00278 current_pose.toPoseMsg(marker1.pose);
00279 marker1.pose.position.x += front_offset_*dir.x();
00280 marker1.pose.position.y += front_offset_*dir.y();
00281 marker1.scale.x = marker1.scale.y = 2*front_radius_;
00282
00283 marker1.color = color;
00284
00285 }
00286 if (rear_radius_>0)
00287 {
00288 markers.push_back(visualization_msgs::Marker());
00289 visualization_msgs::Marker& marker2 = markers.back();
00290 marker2.type = visualization_msgs::Marker::CYLINDER;
00291 current_pose.toPoseMsg(marker2.pose);
00292 marker2.pose.position.x -= rear_offset_*dir.x();
00293 marker2.pose.position.y -= rear_offset_*dir.y();
00294 marker2.scale.x = marker2.scale.y = 2*rear_radius_;
00295
00296 marker2.color = color;
00297 }
00298 }
00299
00300 private:
00301
00302 double front_offset_;
00303 double front_radius_;
00304 double rear_offset_;
00305 double rear_radius_;
00306
00307 };
00308
00309
00310
00315 class LineRobotFootprint : public BaseRobotFootprintModel
00316 {
00317 public:
00318
00324 LineRobotFootprint(const geometry_msgs::Point& line_start, const geometry_msgs::Point& line_end)
00325 {
00326 setLine(line_start, line_end);
00327 }
00328
00334 LineRobotFootprint(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end)
00335 {
00336 setLine(line_start, line_end);
00337 }
00338
00342 virtual ~LineRobotFootprint() { }
00343
00348 void setLine(const geometry_msgs::Point& line_start, const geometry_msgs::Point& line_end)
00349 {
00350 line_start_.x() = line_start.x;
00351 line_start_.y() = line_start.y;
00352 line_end_.x() = line_end.x;
00353 line_end_.y() = line_end.y;
00354 }
00355
00360 void setLine(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end)
00361 {
00362 line_start_ = line_start;
00363 line_end_ = line_end;
00364 }
00365
00372 virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
00373 {
00374
00375 double cos_th = std::cos(current_pose.theta());
00376 double sin_th = std::sin(current_pose.theta());
00377 Eigen::Vector2d line_start_world;
00378 line_start_world.x() = current_pose.x() + cos_th * line_start_.x() - sin_th * line_start_.y();
00379 line_start_world.y() = current_pose.y() + sin_th * line_start_.x() + cos_th * line_start_.y();
00380 Eigen::Vector2d line_end_world;
00381 line_end_world.x() = current_pose.x() + cos_th * line_end_.x() - sin_th * line_end_.y();
00382 line_end_world.y() = current_pose.y() + sin_th * line_end_.x() + cos_th * line_end_.y();
00383 return obstacle->getMinimumDistance(line_start_world, line_end_world);
00384 }
00385
00394 virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers ) const
00395 {
00396 std_msgs::ColorRGBA color;
00397 color.a = 0.5;
00398 color.r = 0.0;
00399 color.g = 0.8;
00400 color.b = 0.0;
00401
00402 markers.push_back(visualization_msgs::Marker());
00403 visualization_msgs::Marker& marker = markers.front();
00404 marker.type = visualization_msgs::Marker::LINE_STRIP;
00405 current_pose.toPoseMsg(marker.pose);
00406
00407
00408 geometry_msgs::Point line_start_world;
00409 line_start_world.x = line_start_.x();
00410 line_start_world.y = line_start_.y();
00411 line_start_world.z = 0;
00412 marker.points.push_back(line_start_world);
00413
00414 geometry_msgs::Point line_end_world;
00415 line_end_world.x = line_end_.x();
00416 line_end_world.y = line_end_.y();
00417 line_end_world.z = 0;
00418 marker.points.push_back(line_end_world);
00419
00420 marker.scale.x = 0.05;
00421 marker.color = color;
00422 }
00423
00424 private:
00425
00426 Eigen::Vector2d line_start_;
00427 Eigen::Vector2d line_end_;
00428
00429 public:
00430 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00431
00432 };
00433
00434
00435
00440 class PolygonRobotFootprint : public BaseRobotFootprintModel
00441 {
00442 public:
00443
00444
00445
00450 PolygonRobotFootprint(const Point2dContainer& vertices) : vertices_(vertices) { }
00451
00455 virtual ~PolygonRobotFootprint() { }
00456
00461 void setVertices(const Point2dContainer& vertices) {vertices_ = vertices;}
00462
00469 virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
00470 {
00471
00472 double cos_th = std::cos(current_pose.theta());
00473 double sin_th = std::sin(current_pose.theta());
00474 Point2dContainer polygon_world(vertices_.size());
00475 for (std::size_t i=0; i<vertices_.size(); ++i)
00476 {
00477 polygon_world[i].x() = current_pose.x() + cos_th * vertices_[i].x() - sin_th * vertices_[i].y();
00478 polygon_world[i].y() = current_pose.y() + sin_th * vertices_[i].x() + cos_th * vertices_[i].y();
00479 }
00480 return obstacle->getMinimumDistance(polygon_world);
00481 }
00482
00491 virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers ) const
00492 {
00493 if (vertices_.empty())
00494 return;
00495
00496 std_msgs::ColorRGBA color;
00497 color.a = 0.5;
00498 color.r = 0.0;
00499 color.g = 0.8;
00500 color.b = 0.0;
00501
00502 markers.push_back(visualization_msgs::Marker());
00503 visualization_msgs::Marker& marker = markers.front();
00504 marker.type = visualization_msgs::Marker::LINE_STRIP;
00505 current_pose.toPoseMsg(marker.pose);
00506
00507 for (std::size_t i = 0; i < vertices_.size(); ++i)
00508 {
00509 geometry_msgs::Point point;
00510 point.x = vertices_[i].x();
00511 point.y = vertices_[i].y();
00512 point.z = 0;
00513 marker.points.push_back(point);
00514 }
00515
00516 geometry_msgs::Point point;
00517 point.x = vertices_.front().x();
00518 point.y = vertices_.front().y();
00519 point.z = 0;
00520 marker.points.push_back(point);
00521
00522 marker.scale.x = 0.025;
00523 marker.color = color;
00524
00525 }
00526
00527 private:
00528
00529 Point2dContainer vertices_;
00530
00531 };
00532
00533
00534
00535
00536
00537 }
00538
00539 #endif