$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 00040 #include <flirtlib_ros/flirtlib.h> 00041 00042 #include <flirtlib_ros/conversions.h> 00043 #include <visualization_msgs/Marker.h> 00044 #include <ros/ros.h> 00045 #include <tf/transform_listener.h> 00046 #include <boost/thread.hpp> 00047 #include <boost/foreach.hpp> 00048 #include <boost/lexical_cast.hpp> 00049 00050 namespace sm=sensor_msgs; 00051 namespace vm=visualization_msgs; 00052 namespace gm=geometry_msgs; 00053 00054 using std::string; 00055 using std::vector; 00056 00057 typedef boost::mutex::scoped_lock Lock; 00058 typedef vector<InterestPoint*> InterestPointVec; 00059 typedef std::pair<InterestPoint*, InterestPoint*> Correspondence; 00060 typedef vector<Correspondence> Correspondences; 00061 00062 namespace flirtlib_ros 00063 { 00064 00065 /************************************************************ 00066 * Utilities 00067 ***********************************************************/ 00068 00069 gm::Point toPoint (const tf::Vector3& p) 00070 { 00071 gm::Point pt; 00072 pt.x = p.x(); 00073 pt.y = p.y(); 00074 pt.z = p.z(); 00075 return pt; 00076 } 00077 00078 double averageDistance (const Correspondences& corresp, 00079 const gm::Pose& p0, 00080 const gm::Pose& p1) 00081 { 00082 const unsigned n = corresp.size(); 00083 if (n<2) 00084 return 1e17; 00085 00086 tf::Transform pose0, pose1; 00087 tf::poseMsgToTF(p0, pose0); 00088 tf::poseMsgToTF(p1, pose1); 00089 double sum = 0; 00090 00091 BOOST_FOREACH (const Correspondence& c, corresp) 00092 { 00093 const btVector3 pt0(c.first->getPosition().x, c.first->getPosition().y, 0.0); 00094 const btVector3 pt1(c.second->getPosition().x, c.second->getPosition().y, 0.0); 00095 sum += (pose0*pt0).distance(pose1*pt1); 00096 } 00097 return sum/n; 00098 } 00099 00100 /************************************************************ 00101 * Node class 00102 ***********************************************************/ 00103 00104 class Node 00105 { 00106 public: 00107 Node (); 00108 00109 void mainLoop (const ros::TimerEvent& e); 00110 void scanCB (unsigned i, const sm::LaserScan::ConstPtr& scan); 00111 00112 private: 00113 00114 // Needed during initialization 00115 boost::mutex mutex_; 00116 ros::NodeHandle nh_; 00117 00118 // State 00119 vector<sm::LaserScan::ConstPtr> scan_; 00120 00121 // Flirtlib objects 00122 boost::shared_ptr<SimpleMinMaxPeakFinder> peak_finder_; 00123 boost::shared_ptr<HistogramDistance<double> > histogram_dist_; 00124 boost::shared_ptr<Detector> detector_; 00125 boost::shared_ptr<DescriptorGenerator> descriptor_; 00126 boost::shared_ptr<RansacFeatureSetMatcher> ransac_; 00127 00128 // Ros objects 00129 ros::Subscriber scan_subs_[2]; 00130 ros::Publisher marker_pub_; 00131 tf::TransformListener tf_; 00132 ros::Timer exec_timer_; 00133 00134 }; 00135 00136 00137 /************************************************************ 00138 * Initialization 00139 ***********************************************************/ 00140 00141 00142 SimpleMinMaxPeakFinder* createPeakFinder () 00143 { 00144 return new SimpleMinMaxPeakFinder(0.34, 0.001); 00145 } 00146 00147 Detector* createDetector (SimpleMinMaxPeakFinder* peak_finder) 00148 { 00149 const double scale = 5.0; 00150 const double dmst = 2.0; 00151 const double base_sigma = 0.2; 00152 const double sigma_step = 1.4; 00153 CurvatureDetector* det = new CurvatureDetector(peak_finder, scale, base_sigma, 00154 sigma_step, dmst); 00155 det->setUseMaxRange(false); 00156 return det; 00157 } 00158 00159 DescriptorGenerator* createDescriptor (HistogramDistance<double>* dist) 00160 { 00161 const double min_rho = 0.02; 00162 const double max_rho = 0.5; 00163 const double bin_rho = 4; 00164 const double bin_phi = 12; 00165 BetaGridGenerator* gen = new BetaGridGenerator(min_rho, max_rho, bin_rho, 00166 bin_phi); 00167 gen->setDistanceFunction(dist); 00168 return gen; 00169 } 00170 00171 Node::Node () : 00172 scan_(2), peak_finder_(createPeakFinder()), 00173 histogram_dist_(new SymmetricChi2Distance<double>()), 00174 detector_(createDetector(peak_finder_.get())), 00175 descriptor_(createDescriptor(histogram_dist_.get())), 00176 ransac_(new RansacFeatureSetMatcher(0.0599, 0.95, 0.4, 0.4, 00177 0.0384, false)), 00178 00179 marker_pub_(nh_.advertise<vm::Marker>("visualization_marker", 10)), 00180 exec_timer_(nh_.createTimer(ros::Duration(0.2), &Node::mainLoop, this)) 00181 { 00182 for (unsigned i=0; i<2; i++) 00183 { 00184 const string topic = "scan" + boost::lexical_cast<string>(i); 00185 scan_subs_[i] = nh_.subscribe<sm::LaserScan>(topic, 10, 00186 boost::bind(&Node::scanCB, this, i, _1)); 00187 } 00188 } 00189 00190 00191 00192 /************************************************************ 00193 * Visualization 00194 ***********************************************************/ 00195 00196 00197 // Generate markers to visualize correspondences between two scans 00198 vm::Marker correspondenceMarkers (const Correspondences& correspondences, 00199 const gm::Pose& p0, const gm::Pose& p1) 00200 { 00201 vm::Marker m; 00202 m.header.frame_id = "/map"; 00203 m.header.stamp = ros::Time::now(); 00204 m.ns = "flirtlib"; 00205 m.id = 42; 00206 m.type = vm::Marker::LINE_LIST; 00207 m.scale.x = 0.05; 00208 m.color.r = m.color.a = 1.0; 00209 m.color.g = 0.65; 00210 tf::Pose pose0, pose1; 00211 tf::poseMsgToTF(p0, pose0); 00212 tf::poseMsgToTF(p1, pose1); 00213 00214 BOOST_FOREACH (const Correspondence& c, correspondences) 00215 { 00216 const tf::Vector3 pt0(c.first->getPosition().x, c.first->getPosition().y, 0.0); 00217 const tf::Vector3 pt1(c.second->getPosition().x, c.second->getPosition().y, 0.0); 00218 m.points.push_back(toPoint(pose0*pt0)); 00219 m.points.push_back(toPoint(pose1*pt1)); 00220 } 00221 00222 return m; 00223 } 00224 00225 /************************************************************ 00226 * Callbacks 00227 ***********************************************************/ 00228 00229 void Node::scanCB (const unsigned i, const sm::LaserScan::ConstPtr& scan) 00230 { 00231 Lock l(mutex_); 00232 scan_[i] = scan; 00233 } 00234 00235 00236 /************************************************************ 00237 * Main loop 00238 ***********************************************************/ 00239 00240 00241 void Node::mainLoop (const ros::TimerEvent& e) 00242 { 00243 Lock l(mutex_); 00244 if (!scan_[0] || !scan_[1]) 00245 { 00246 ROS_INFO_THROTTLE (1.0, "Waiting till scans received"); 00247 return; 00248 } 00249 00250 try 00251 { 00252 gm::Pose pose[2]; 00253 InterestPointVec pts[2]; 00254 boost::shared_ptr<LaserReading> reading[2]; 00255 00256 for (unsigned i=0; i<2; i++) 00257 { 00258 // Get the poses 00259 // This part can throw a tf exception 00260 tf::StampedTransform trans; 00261 const string frame = "pose"+boost::lexical_cast<string>(i); 00262 tf_.lookupTransform("/map", frame, ros::Time(), trans); 00263 tf::poseTFToMsg(trans, pose[i]); 00264 00265 // Convert scans to flirtlib 00266 reading[i] = fromRos(*scan_[i]); 00267 00268 // Interest point detection 00269 detector_->detect(*reading[i], pts[i]); 00270 marker_pub_.publish(interestPointMarkers(pts[i], pose[i], i)); 00271 00272 // Descriptor computation 00273 BOOST_FOREACH (InterestPoint* p, pts[i]) 00274 p->setDescriptor(descriptor_->describe(*p, *reading[i])); 00275 00276 } 00277 00278 // Feature matching 00279 Correspondences matches; 00280 OrientedPoint2D transform; 00281 const double score = ransac_->matchSets(pts[0], pts[1], transform, matches); 00282 ROS_INFO_THROTTLE (1.0, "Found %zu matches, with score %.4f, transform " 00283 "(%.2f, %.2f, %.2f), avg dist %.2f", matches.size(), 00284 score, transform.x, transform.y, transform.theta, 00285 averageDistance(matches, pose[1], pose[0])); 00286 marker_pub_.publish(correspondenceMarkers(matches, pose[1], pose[0])); 00287 00288 00289 // Free memory 00290 for (unsigned i=0; i<2; i++) 00291 { 00292 BOOST_FOREACH (const InterestPoint* p, pts[i]) 00293 delete p; 00294 } 00295 } 00296 catch (tf::TransformException& e) 00297 { 00298 ROS_INFO("Skipping frame due to transform exception"); 00299 } 00300 } 00301 00302 00303 00304 } // namespace 00305 00306 int main (int argc, char** argv) 00307 { 00308 ros::init(argc, argv, "flirtlib_ros_test"); 00309 flirtlib_ros::Node node; 00310 ros::spin(); 00311 return 0; 00312 }