00001 #include <ros/ros.h> 00002 #include <ros/console.h> // to change the log level to debug 00003 00004 #include <lama_msgs/Crossing.h> 00005 #include <lama_msgs/PlaceProfile.h> 00006 00007 #include <crossing_detector/laser_crossing_detector.h> 00008 #include <crossing_detector/LaserDetectCrossing.h> 00009 00010 crossing_detector::LaserCrossingDetector* detector; 00011 00012 bool detect_crossing_callback(crossing_detector::LaserDetectCrossing::Request& req, crossing_detector::LaserDetectCrossing::Response& res) 00013 { 00014 detector->setFrontierWidth(req.frontier_width); 00015 detector->setMaxFrontierAngle(req.max_frontier_angle); 00016 detector->setMinRelevance(req.min_relevance); 00017 res.crossing = detector->crossingDescriptor(req.scan, true); 00018 return true; 00019 } 00020 00021 int main(int argc, char *argv[]) 00022 { 00023 ros::init(argc, argv, "crossing_detector"); 00024 ros::NodeHandle nh("~"); 00025 00026 // Change log level. 00027 if(ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Debug)) 00028 { 00029 ros::console::notifyLoggerLevelsChanged(); 00030 } 00031 00032 detector = new crossing_detector::LaserCrossingDetector(0); 00033 00034 ros::ServiceServer service_server = nh.advertiseService("detect_crossing", detect_crossing_callback); 00035 00036 ros::spin(); 00037 return 0; 00038 }