costmap_crossing_detector.h
Go to the documentation of this file.
00001 
00005 #ifndef _CROSSING_DETECTOR_COSTMAP_CROSSING_DETECTOR_H_
00006 #define _CROSSING_DETECTOR_COSTMAP_CROSSING_DETECTOR_H_
00007 
00008 #include <nav_msgs/OccupancyGrid.h>
00009 
00010 #include <lama_common/place_profile_conversions.h>
00011 
00012 #include <crossing_detector/crossing_detector.h>
00013 
00014 namespace crossing_detector
00015 {
00016 
00017 using nav_msgs::OccupancyGrid;
00018 
00019 class CostmapCrossingDetector : public CrossingDetector
00020 {
00021   public:
00022     
00023     CostmapCrossingDetector(const double frontier_width, const double max_frontier_angle=0.785);
00024 
00025     Crossing crossingDescriptor(const OccupancyGrid& map, double range_cutoff = 0);
00026     vector<Frontier> frontiers(const OccupancyGrid& map, double range_cutoff = 0);
00027 
00028   private:
00029     
00030     // Visibility change (not necessary).
00031     using CrossingDetector::crossingDescriptor;
00032     using CrossingDetector::frontiers;
00033 };
00034 
00035 } // namespace crossing_detector
00036 
00037 #endif //  _CROSSING_DETECTOR_COSTMAP_CROSSING_DETECTOR_H_
00038 


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