00001 #include <crossing_detector/costmap_crossing_detector.h> 00002 00003 namespace crossing_detector 00004 { 00005 00006 CostmapCrossingDetector::CostmapCrossingDetector(double frontier_width, double max_frontier_angle) : 00007 CrossingDetector(frontier_width, max_frontier_angle) 00008 { 00009 } 00010 00011 Crossing CostmapCrossingDetector::crossingDescriptor(const OccupancyGrid& map, double range_cutoff) 00012 { 00013 PlaceProfile profile = lama_common::costmapToPlaceProfile(map, range_cutoff); 00014 00015 return CrossingDetector::crossingDescriptor(profile); 00016 } 00017 00018 vector<Frontier> CostmapCrossingDetector::frontiers(const OccupancyGrid& map, double range_cutoff) 00019 { 00020 PlaceProfile profile = lama_common::costmapToPlaceProfile(map, range_cutoff); 00021 00022 return CrossingDetector::frontiers(profile); 00023 } 00024 00025 } // namespace crossing_detector 00026