#include <flirtlib.h>
Public Member Functions | |
InterestPointVec | extractFeatures (sensor_msgs::LaserScan::ConstPtr scan) const |
FlirtlibFeatures (ros::NodeHandle nh=ros::NodeHandle("~")) | |
Public Attributes | |
boost::shared_ptr < DescriptorGenerator > | descriptor_ |
boost::shared_ptr< Detector > | detector_ |
boost::shared_ptr < HistogramDistance< double > > | histogram_dist_ |
boost::shared_ptr < SimpleMinMaxPeakFinder > | peak_finder_ |
boost::shared_ptr < RansacFeatureSetMatcher > | ransac_ |
Definition at line 67 of file flirtlib.h.
Initialize Flirtlib objects based on ros parameters. Specifying the node handle argument allows selecting the ros namespace in which the parameters will be searched for.
Definition at line 74 of file flirtlib.cpp.
InterestPointVec flirtlib_ros::FlirtlibFeatures::extractFeatures | ( | sensor_msgs::LaserScan::ConstPtr | scan | ) | const |
Definition at line 87 of file flirtlib.cpp.
boost::shared_ptr<DescriptorGenerator> flirtlib_ros::FlirtlibFeatures::descriptor_ |
Definition at line 77 of file flirtlib.h.
boost::shared_ptr<Detector> flirtlib_ros::FlirtlibFeatures::detector_ |
Definition at line 76 of file flirtlib.h.
boost::shared_ptr<HistogramDistance<double> > flirtlib_ros::FlirtlibFeatures::histogram_dist_ |
Definition at line 75 of file flirtlib.h.
boost::shared_ptr<SimpleMinMaxPeakFinder> flirtlib_ros::FlirtlibFeatures::peak_finder_ |
Definition at line 74 of file flirtlib.h.
boost::shared_ptr<RansacFeatureSetMatcher> flirtlib_ros::FlirtlibFeatures::ransac_ |
Definition at line 78 of file flirtlib.h.