Go to the documentation of this file.00001 #include <crossing_detector/laser_crossing_detector.h>
00002
00003 namespace crossing_detector
00004 {
00005
00006 LaserCrossingDetector::LaserCrossingDetector(const double frontier_width, const double max_frontier_angle) :
00007 CrossingDetector(frontier_width, max_frontier_angle),
00008 range_cutoff_(0)
00009 {
00010 ros::NodeHandle private_nh("~");
00011 private_nh.getParam("range_cutoff", range_cutoff_);
00012 }
00013
00014 Crossing LaserCrossingDetector::crossingDescriptor(const LaserScan& scan, const bool normalize)
00015 {
00016 double max_range = range_cutoff_;
00017 if (std::abs(range_cutoff_) < 1e-10)
00018 {
00019 max_range = 0.9 * scan.range_max;
00020 }
00021
00022 PlaceProfile profile = lama_common::laserScanToPlaceProfile(scan, max_range);
00023
00024 return CrossingDetector::crossingDescriptor(profile, normalize);
00025 }
00026
00027 vector<Frontier> LaserCrossingDetector::frontiers(const LaserScan& scan, const bool normalize)
00028 {
00029 double max_range = range_cutoff_;
00030 if (std::abs(range_cutoff_) < 1e-10)
00031 {
00032 max_range = 0.9 * scan.range_max;
00033 }
00034
00035 PlaceProfile profile = lama_common::laserScanToPlaceProfile(scan, max_range);
00036
00037 return CrossingDetector::frontiers(profile, normalize);
00038 }
00039
00040 }
00041
00042