$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 00041 #include <flirtlib_ros/conversions.h> 00042 #include <mongo_ros/message_collection.h> 00043 #include <tf/transform_listener.h> 00044 #include <visualization_msgs/Marker.h> 00045 #include <ros/ros.h> 00046 00047 namespace flirtlib_ros 00048 { 00049 00050 namespace sm=sensor_msgs; 00051 namespace gm=geometry_msgs; 00052 namespace mr=mongo_ros; 00053 namespace vm=visualization_msgs; 00054 using std::vector; 00055 using std::string; 00056 00057 typedef boost::mutex::scoped_lock Lock; 00058 typedef vector<InterestPoint*> InterestPointVec; 00059 00060 class Node 00061 { 00062 public: 00063 00064 Node(); 00065 void scanCB (sm::LaserScan::ConstPtr scan); 00066 00067 private: 00068 00069 bool haveNearbyScan (const gm::Pose& pose) const; 00070 gm::Pose getPoseAt (const ros::Time& t) const; 00071 RefScanRos extractFeatures (sm::LaserScan::ConstPtr scan, 00072 const gm::Pose& pose); 00073 00074 // Needed during init 00075 boost::mutex mutex_; 00076 ros::NodeHandle nh_; 00077 00078 // Parameters 00079 const double pos_inc_, theta_inc_; 00080 00081 // Flirtlib objects 00082 FlirtlibFeatures features_; 00083 00084 // Ros objects 00085 tf::TransformListener tf_; 00086 ros::Subscriber scan_sub_; 00087 ros::Publisher marker_pub_; 00088 mr::MessageCollection<RefScanRos> scans_; 00089 00090 }; 00091 00092 /************************************************************ 00093 * Initialization 00094 ***********************************************************/ 00095 00096 template <class T> 00097 T getPrivateParam (const string& name) 00098 { 00099 ros::NodeHandle nh("~"); 00100 T val; 00101 const bool found = nh.getParam(name, val); 00102 ROS_ASSERT_MSG (found, "Could not find parameter %s", name.c_str()); 00103 ROS_DEBUG_STREAM_NAMED ("init", "Initialized " << name << " to " << val); 00104 return val; 00105 } 00106 00107 Node::Node () : 00108 pos_inc_(getPrivateParam<double>("pos_inc")), 00109 theta_inc_(getPrivateParam<double>("theta_inc")), 00110 features_(ros::NodeHandle("~")), 00111 scan_sub_(nh_.subscribe("scan", 1, &Node::scanCB, this)), 00112 marker_pub_(nh_.advertise<vm::Marker>("visualization_marker", 10)), 00113 scans_(getPrivateParam<string>("scan_db"), "scans") 00114 { 00115 ROS_ASSERT_MSG(scans_.count()==0, "Scan collection was not empty"); 00116 scans_.ensureIndex("x"); 00117 ROS_INFO ("generate_scan_map initialized"); 00118 } 00119 00120 /************************************************************ 00121 * Localization 00122 ***********************************************************/ 00123 00124 inline 00125 double angleDist (double t1, double t2) 00126 { 00127 if (t2<t1) 00128 std::swap(t1,t2); 00129 const double d = t2-t1; 00130 return std::min(d, 6.2832-d); 00131 } 00132 00133 bool Node::haveNearbyScan (const gm::Pose& pose) const 00134 { 00135 using mongo::GT; 00136 using mongo::LT; 00137 00138 bool found = false; 00139 const double x = pose.position.x; 00140 const double y = pose.position.y; 00141 const double theta = tf::getYaw(pose.orientation); 00142 00143 // Query for scans in a box around current pose 00144 mongo::Query q = BSON("x" << GT << x-pos_inc_ << LT << x+pos_inc_ << 00145 "y" << GT << y-pos_inc_ << LT << y+pos_inc_); 00146 BOOST_FOREACH (mr::MessageWithMetadata<RefScanRos>::ConstPtr scan, 00147 scans_.queryResults(q, true)) 00148 { 00149 // Also check angle distance 00150 if (angleDist(theta, scan->lookupDouble("theta")) < theta_inc_) 00151 found = true; 00152 } 00153 return found; 00154 } 00155 00156 gm::Pose Node::getPoseAt (const ros::Time& t) const 00157 { 00158 tf::StampedTransform trans; 00159 tf_.waitForTransform("/map", "base_laser_link", t, ros::Duration(0.5)); 00160 tf_.lookupTransform("/map", "base_laser_link", t, trans); 00161 gm::Pose pose; 00162 tf::poseTFToMsg(trans, pose); 00163 return pose; 00164 } 00165 00166 /************************************************************ 00167 * Processing scans 00168 ***********************************************************/ 00169 00170 RefScanRos Node::extractFeatures (sm::LaserScan::ConstPtr scan, 00171 const gm::Pose& pose) 00172 { 00173 boost::shared_ptr<LaserReading> reading = fromRos(*scan); 00174 InterestPointVec pts; 00175 features_.detector_->detect(*reading, pts); 00176 BOOST_FOREACH (InterestPoint* p, pts) 00177 p->setDescriptor(features_.descriptor_->describe(*p, *reading)); 00178 marker_pub_.publish(interestPointMarkers(pts, pose)); 00179 const RefScan ref(scan, pose, pts); 00180 return toRos(ref); 00181 } 00182 00183 00184 void Node::scanCB (sm::LaserScan::ConstPtr scan) 00185 { 00186 try 00187 { 00188 const gm::Pose pose = getPoseAt(scan->header.stamp); // can throw 00189 if (haveNearbyScan(pose)) 00190 return; 00191 00192 // Now guaranteed no nearby pose 00193 const double x = pose.position.x; 00194 const double y = pose.position.y; 00195 const double th = tf::getYaw(pose.orientation); 00196 00197 scans_.insert(extractFeatures(scan, pose), 00198 mr::Metadata("x", x, "y", y, "theta", th)); 00199 ROS_DEBUG_NAMED ("save_scan", "Saved scan at %.2f, %.2f, %.2f", x, y, th); 00200 } 00201 catch (tf::TransformException& e) 00202 { 00203 ROS_INFO ("Skipping callback due to tf error: '%s'", e.what()); 00204 } 00205 00206 } 00207 00208 } // namespace 00209 00210 int main (int argc, char** argv) 00211 { 00212 ros::init(argc, argv, "generate_scan_map"); 00213 flirtlib_ros::Node node; 00214 ros::spin(); 00215 return 0; 00216 }