crossing_detector.h
Go to the documentation of this file.
00001 /*
00002  * Crossing detector from lama_msgs/PlaceProfile.msg
00003  */
00004 
00005 #ifndef _CROSSING_DETECTOR_CROSSING_DETECTOR_H_
00006 #define _CROSSING_DETECTOR_CROSSING_DETECTOR_H_
00007 
00008 #include <cmath>
00009 #include <cstring>
00010 #include <vector>
00011 
00012 #include <CGAL/Exact_predicates_inexact_constructions_kernel.h>
00013 #include <CGAL/Delaunay_triangulation_2.h>
00014 #include <CGAL/Polygon_2.h>
00015 
00016 #include <ros/ros.h>
00017 #include <geometry_msgs/Polygon.h>
00018 
00019 #include <lama_common/place_profile_utils.h>
00020 #include <lama_msgs/Crossing.h>
00021 #include <lama_msgs/Frontier.h>
00022 #include <lama_msgs/PlaceProfile.h>
00023 
00024 namespace crossing_detector
00025 {
00026 
00027 using std::vector;
00028 using lama_msgs::Crossing;
00029 using lama_msgs::PlaceProfile;
00030 using lama_msgs::Frontier;
00031 
00032 typedef CGAL::Exact_predicates_inexact_constructions_kernel K;
00033 typedef K::Point_2 Point;
00034 typedef CGAL::Delaunay_triangulation_2<K> Delaunay;
00035 typedef Delaunay::Face_iterator Face_iterator;
00036 typedef CGAL::Polygon_2<K> Polygon;
00037 
00038 class CrossingDetector
00039 {
00040   public:
00041 
00042     CrossingDetector(const double frontier_width, const double max_frontier_angle=1.0);
00043 
00044     Crossing crossingDescriptor(const PlaceProfile& profile, const bool normalize=false);
00045     vector<Frontier> frontiers(const PlaceProfile& profile, const bool normalize=false);
00046 
00047     double getFrontierWidth() const {return frontier_width_;}
00048     void setFrontierWidth(const double value) {frontier_width_ = std::fabs(value);}
00049 
00050     double getMaxFrontierAngle() const {return max_frontier_angle_;}
00051     void setMaxFrontierAngle(const double value) {max_frontier_angle_ = std::fabs(value);}
00052 
00053     double getMinRelevance() const {return min_relevance_;}
00054     void setMinRelevance(const double value) {min_relevance_ = std::fabs(value);}
00055 
00056     PlaceProfile getPlaceProfile() const {return place_profile_;}
00057 
00058   protected:
00059 
00060     vector<Frontier> frontiers_() const;
00061 
00062     PlaceProfile place_profile_;  
00063 
00064   private:
00065 
00066     vector<Point> delaunayInput(const PlaceProfile& profile) const;
00067 
00068     // Parameters shown outside (constructor and setter).
00069     double frontier_width_;  
00070     double max_frontier_angle_;  
00071 
00072 
00073     double min_relevance_;  
00074 
00075 };
00076 
00077 } // namespace crossing_detector
00078 
00079 #endif // _CROSSING_DETECTOR_CROSSING_DETECTOR_H_
00080 


crossing_detector
Author(s): Gaël Ecorchard , Karel Košnar , Vojtěch Vonásek
autogenerated on Thu Jun 6 2019 22:02:06