Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00040 #ifndef FLIRTLIB_ROS_FLIRTLIB_H
00041 #define FLIRTLIB_ROS_FLIRTLIB_H
00042
00043 #define BOOST_NO_HASH
00044
00045 #include <flirtlib/feature/Detector.h>
00046 #include <flirtlib/feature/ShapeContext.h>
00047 #include <flirtlib/feature/BetaGrid.h>
00048 #include <flirtlib/feature/RangeDetector.h>
00049 #include <flirtlib/feature/CurvatureDetector.h>
00050 #include <flirtlib/feature/NormalBlobDetector.h>
00051 #include <flirtlib/feature/NormalEdgeDetector.h>
00052 #include <flirtlib/feature/RansacFeatureSetMatcher.h>
00053 #include <flirtlib/feature/RansacMultiFeatureSetMatcher.h>
00054 #include <flirtlib/sensorstream/CarmenLog.h>
00055 #include <flirtlib/sensorstream/LogSensorStream.h>
00056 #include <flirtlib/sensorstream/SensorStream.h>
00057 #include <flirtlib/utils/SimpleMinMaxPeakFinder.h>
00058 #include <flirtlib/utils/HistogramDistances.h>
00059 #include <sensor_msgs/LaserScan.h>
00060 #include <ros/ros.h>
00061
00062 namespace flirtlib_ros
00063 {
00064
00065 typedef std::vector<InterestPoint*> InterestPointVec;
00066
00067 struct FlirtlibFeatures
00068 {
00072 FlirtlibFeatures (ros::NodeHandle nh = ros::NodeHandle("~"));
00073
00074 boost::shared_ptr<SimpleMinMaxPeakFinder> peak_finder_;
00075 boost::shared_ptr<HistogramDistance<double> > histogram_dist_;
00076 boost::shared_ptr<Detector> detector_;
00077 boost::shared_ptr<DescriptorGenerator> descriptor_;
00078 boost::shared_ptr<RansacFeatureSetMatcher> ransac_;
00079
00080 InterestPointVec extractFeatures (sensor_msgs::LaserScan::ConstPtr scan) const;
00081 };
00082
00083 }
00084
00085 #endif // include guard