00001 00005 #ifndef _CROSSING_DETECTOR_LASER_CROSSING_DETECTOR_H_ 00006 #define _CROSSING_DETECTOR_LASER_CROSSING_DETECTOR_H_ 00007 00008 #include <cmath> // for std::abs 00009 00010 #include <ros/ros.h> 00011 #include <sensor_msgs/LaserScan.h> 00012 00013 #include <lama_common/place_profile_conversions.h> 00014 00015 #include <crossing_detector/crossing_detector.h> 00016 00017 namespace crossing_detector 00018 { 00019 00020 using sensor_msgs::LaserScan; 00021 00022 class LaserCrossingDetector : public CrossingDetector 00023 { 00024 public: 00025 00026 LaserCrossingDetector(const double frontier_width, const double max_frontier_angle=0.785); 00027 00028 Crossing crossingDescriptor(const LaserScan& scan, const bool normalize=false); 00029 vector<lama_msgs::Frontier> frontiers(const LaserScan& scan, const bool normalize=false); 00030 00031 double getMaxFrontierDistance() const {return range_cutoff_;} 00032 void setMaxFrontierDistance(const double value) {range_cutoff_ = value;} 00033 00034 private: 00035 00036 // Parameters shown outside. 00037 double range_cutoff_; 00038 00039 00040 // Internals. 00041 00042 // Visibility change (not necessary). 00043 using CrossingDetector::crossingDescriptor; 00044 using CrossingDetector::frontiers; 00045 }; 00046 00047 } // namespace crossing_detector 00048 00049 #endif // _CROSSING_DETECTOR_LASER_CROSSING_DETECTOR_H_