$search
00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 * 00029 */ 00030 00039 #include <flirtlib_ros/flirtlib.h> 00040 #include <flirtlib_ros/conversions.h> 00041 #include <boost/foreach.hpp> 00042 00043 namespace flirtlib_ros 00044 { 00045 00046 using std::string; 00047 namespace sm=sensor_msgs; 00048 00049 Detector* createDetector (SimpleMinMaxPeakFinder* peak_finder) 00050 { 00051 const double scale = 5.0; 00052 const double dmst = 2.0; 00053 const double base_sigma = 0.2; 00054 const double sigma_step = 1.4; 00055 CurvatureDetector* det = new CurvatureDetector(peak_finder, scale, base_sigma, 00056 sigma_step, dmst); 00057 det->setUseMaxRange(false); 00058 return det; 00059 } 00060 00061 DescriptorGenerator* createDescriptor (HistogramDistance<double>* dist) 00062 { 00063 const double min_rho = 0.02; 00064 const double max_rho = 0.5; 00065 const double bin_rho = 4; 00066 const double bin_phi = 12; 00067 BetaGridGenerator* gen = new BetaGridGenerator(min_rho, max_rho, bin_rho, 00068 bin_phi); 00069 gen->setDistanceFunction(dist); 00070 return gen; 00071 } 00072 00073 00074 FlirtlibFeatures::FlirtlibFeatures (ros::NodeHandle nh) 00075 { 00076 ROS_INFO("Note: currently ignoring ros params and using hardcoded params"); 00077 peak_finder_.reset(new SimpleMinMaxPeakFinder(0.34, 0.001)); 00078 histogram_dist_.reset(new SymmetricChi2Distance<double>()); 00079 detector_.reset(createDetector(peak_finder_.get())); 00080 descriptor_.reset(createDescriptor(histogram_dist_.get())); 00081 ransac_.reset(new RansacFeatureSetMatcher(0.0599, 0.95, 0.4, 0.4, 00082 0.0384, false)); 00083 } 00084 00085 // Extract flirtlib features 00086 InterestPointVec 00087 FlirtlibFeatures::extractFeatures (sm::LaserScan::ConstPtr scan) const 00088 { 00089 boost::shared_ptr<LaserReading> reading = fromRos(*scan); 00090 InterestPointVec pts; 00091 detector_->detect(*reading, pts); 00092 BOOST_FOREACH (InterestPoint* p, pts) 00093 p->setDescriptor(descriptor_->describe(*p, *reading)); 00094 return pts; 00095 } 00096 00097 00098 00099 } // namespace