$search
00001 /* 00002 * Copyright (c) 2010, Thomas Ruehr <ruehr@cs.tum.edu> 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 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 #include <ros/ros.h> 00031 00032 #include <std_msgs/String.h> 00033 #include <sensor_msgs/PointCloud.h> 00034 #include <sensor_msgs/PointCloud2.h> 00035 #include <nav_msgs/OccupancyGrid.h> 00036 //for point_cloud::fromROSMsg 00037 #include <pcl/ros/conversions.h> 00038 #include <sensor_msgs/point_cloud_conversion.h> 00039 #include <sensor_msgs/LaserScan.h> 00040 #include <pcl/point_types.h> 00041 #include <pcl/io/pcd_io.h> 00042 #include <laser_geometry/laser_geometry.h> 00043 #include <tf/transform_listener.h> 00044 00045 #include <pcl/registration/icp.h> 00046 #include <pcl/registration/icp_nl.h> 00047 #include <pcl/registration/transforms.h> 00048 #include <pcl/kdtree/kdtree_flann.h> 00049 00050 #include <geometry_msgs/PoseWithCovarianceStamped.h> 00051 00052 #include <boost/thread/mutex.hpp> 00053 00054 boost::mutex scan_callback_mutex; 00055 00056 //these should be parameters 00057 // defines how good the match has to be to create a candidate for publishing a pose 00058 double ICP_FITNESS_THRESHOLD = 100.1;// = 0.025; 00059 //defines how much distance deviation from amcl to icp pose is needed to make us publish a pose 00060 double DIST_THRESHOLD = 0.05; 00061 // same for angle 00062 double ANGLE_THRESHOLD = 0.01; 00063 double ANGLE_UPPER_THRESHOLD = M_PI / 6; 00064 // accept only scans one second old or younger 00065 double AGE_THRESHOLD = 1; 00066 double UPDATE_AGE_THRESHOLD = 1; 00067 00068 double ICP_INLIER_THRESHOLD = 0.9; 00069 double ICP_INLIER_DIST = 0.1; 00070 00071 double POSE_COVARIANCE_TRANS = 1.5; 00072 double ICP_NUM_ITER = 250; 00073 00074 double SCAN_RATE = 2; 00075 00076 std::string BASE_LASER_FRAME = "/base_laser_link"; 00077 std::string ODOM_FRAME = "/odom_combined"; 00078 00079 ros::NodeHandle *nh = 0; 00080 ros::Publisher pub_output_; 00081 ros::Publisher pub_output_scan; 00082 ros::Publisher pub_output_scan_transformed; 00083 ros::Publisher pub_info_; 00084 00085 ros::Publisher pub_pose; 00086 00087 00088 laser_geometry::LaserProjection *projector_ = 0; 00089 tf::TransformListener *listener_ = 0; 00090 sensor_msgs::PointCloud2 cloud2; 00091 sensor_msgs::PointCloud2 cloud2transformed; 00092 00093 typedef pcl::PointCloud<pcl::PointXYZ> PointCloudT; 00094 00095 boost::shared_ptr< sensor_msgs::PointCloud2> output_cloud = boost::shared_ptr<sensor_msgs::PointCloud2>(new sensor_msgs::PointCloud2()); 00096 boost::shared_ptr< sensor_msgs::PointCloud2> scan_cloud = boost::shared_ptr<sensor_msgs::PointCloud2>(new sensor_msgs::PointCloud2()); 00097 00098 bool we_have_a_map = false; 00099 bool we_have_a_scan = false; 00100 bool we_have_a_scan_transformed = false; 00101 00102 bool use_sim_time = false; 00103 00104 int lastScan = 0; 00105 int actScan = 0; 00106 00107 /*inline void 00108 pcl::transformAsMatrix (const tf::Transform& bt, Eigen::Matrix4f &out_mat) 00109 { 00110 double mv[12]; 00111 bt.getBasis ().getOpenGLSubMatrix (mv); 00112 00113 tf::Vector3 origin = bt.getOrigin (); 00114 00115 out_mat (0, 0) = mv[0]; out_mat (0, 1) = mv[4]; out_mat (0, 2) = mv[8]; 00116 out_mat (1, 0) = mv[1]; out_mat (1, 1) = mv[5]; out_mat (1, 2) = mv[9]; 00117 out_mat (2, 0) = mv[2]; out_mat (2, 1) = mv[6]; out_mat (2, 2) = mv[10]; 00118 00119 out_mat (3, 0) = out_mat (3, 1) = out_mat (3, 2) = 0; out_mat (3, 3) = 1; 00120 out_mat (0, 3) = origin.x (); 00121 out_mat (1, 3) = origin.y (); 00122 out_mat (2, 3) = origin.z (); 00123 }*/ 00124 00125 inline void 00126 matrixAsTransfrom (const Eigen::Matrix4f &out_mat, tf::Transform& bt) 00127 { 00128 double mv[12]; 00129 00130 mv[0] = out_mat (0, 0) ; 00131 mv[4] = out_mat (0, 1); 00132 mv[8] = out_mat (0, 2); 00133 mv[1] = out_mat (1, 0) ; 00134 mv[5] = out_mat (1, 1); 00135 mv[9] = out_mat (1, 2); 00136 mv[2] = out_mat (2, 0) ; 00137 mv[6] = out_mat (2, 1); 00138 mv[10] = out_mat (2, 2); 00139 00140 btMatrix3x3 basis; 00141 basis.setFromOpenGLSubMatrix(mv); 00142 tf::Vector3 origin(out_mat (0, 3),out_mat (1, 3),out_mat (2, 3)); 00143 00144 ROS_DEBUG("origin %f %f %f", origin.x(), origin.y(), origin.z()); 00145 00146 bt = tf::Transform(basis,origin); 00147 } 00148 00149 00150 boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ> > cloud_xyz; 00151 00152 pcl::KdTree<pcl::PointXYZ>::Ptr mapTree; 00153 00154 00155 pcl::KdTree<pcl::PointXYZ>::Ptr getTree(pcl::PointCloud<pcl::PointXYZ>::Ptr cloudb) 00156 { 00157 pcl::KdTree<pcl::PointXYZ>::Ptr tree; 00158 tree.reset (new pcl::KdTreeFLANN<pcl::PointXYZ>); 00159 00160 tree->setInputCloud (cloudb); 00161 return tree; 00162 } 00163 00164 00165 void mapCallback(const nav_msgs::OccupancyGrid& msg) 00166 { 00167 ROS_DEBUG("I heard frame_id: [%s]", msg.header.frame_id.c_str()); 00168 00169 float resolution = msg.info.resolution; 00170 float width = msg.info.width; 00171 float height = msg.info.height; 00172 00173 float posx = msg.info.origin.position.x; 00174 float posy = msg.info.origin.position.y; 00175 00176 cloud_xyz = boost::shared_ptr< pcl::PointCloud<pcl::PointXYZ> >(new pcl::PointCloud<pcl::PointXYZ>()); 00177 00178 //cloud_xyz->width = 100; // 100 00179 cloud_xyz->height = 1; 00180 cloud_xyz->is_dense = false; 00181 cloud_xyz->header.stamp = ros::Time(0); 00182 cloud_xyz->header.frame_id = "/map"; 00183 00184 pcl::PointXYZ point_xyz; 00185 00186 //for (unsigned int i = 0; i < cloud_xyz->width ; i++) 00187 for (int y = 0; y < height; y++) 00188 for (int x = 0; x < width; x++) 00189 { 00190 //@TODO 00191 if (msg.data[x + y * width] == 100) 00192 { 00193 point_xyz.x = (.5f + x) * resolution + posx; 00194 point_xyz.y = (.5f + y) * resolution + posy; 00195 point_xyz.z = 0; 00196 cloud_xyz->points.push_back(point_xyz); 00197 } 00198 } 00199 cloud_xyz->width = cloud_xyz->points.size(); 00200 00201 mapTree = getTree(cloud_xyz); 00202 00203 pcl::toROSMsg (*cloud_xyz, *output_cloud); 00204 ROS_DEBUG("Publishing PointXYZ cloud with %ld points in frame %s", cloud_xyz->points.size(),output_cloud->header.frame_id.c_str()); 00205 00206 we_have_a_map = true; 00207 } 00208 00209 00210 int lastTimeSent = -1000; 00211 00212 int count_sc_ = 0; 00213 00214 bool getTransform(tf::StampedTransform &trans , const std::string parent_frame, const std::string child_frame, const ros::Time stamp) 00215 { 00216 bool gotTransform = false; 00217 00218 ros::Time before = ros::Time::now(); 00219 if (!listener_->waitForTransform(parent_frame, child_frame, stamp, ros::Duration(0.5))) 00220 { 00221 ROS_WARN("DIDNT GET TRANSFORM %s %s IN c at %f", parent_frame.c_str(), child_frame.c_str(), stamp.toSec()); 00222 return false; 00223 } 00224 //ROS_INFO("waited for transform %f", (ros::Time::now() - before).toSec()); 00225 00226 try 00227 { 00228 gotTransform = true; 00229 listener_->lookupTransform(parent_frame,child_frame,stamp , trans); 00230 } 00231 catch (tf::TransformException ex) 00232 { 00233 gotTransform = false; 00234 ROS_WARN("DIDNT GET TRANSFORM %s %s IN B", parent_frame.c_str(), child_frame.c_str()); 00235 } 00236 00237 00238 return gotTransform; 00239 } 00240 00241 ros::Time last_processed_scan; 00242 00243 void scanCallback (const sensor_msgs::LaserScan::ConstPtr& scan_in) 00244 { 00245 if (!we_have_a_map) 00246 { 00247 ROS_INFO("SnapMapICP waiting for map to be published"); 00248 return; 00249 } 00250 00251 ros::Time scan_in_time = scan_in->header.stamp; 00252 ros::Time time_received = ros::Time::now(); 00253 00254 if ( scan_in_time - last_processed_scan < ros::Duration(1.0f / SCAN_RATE) ) 00255 { 00256 ROS_DEBUG("rejected scan, last %f , this %f", last_processed_scan.toSec() ,scan_in_time.toSec()); 00257 return; 00258 } 00259 00260 00261 //projector_.transformLaserScanToPointCloud("base_link",*scan_in,cloud,listener_); 00262 if (!scan_callback_mutex.try_lock()) 00263 return; 00264 00265 ros::Duration scan_age = ros::Time::now() - scan_in_time; 00266 00267 //check if we want to accept this scan, if its older than 1 sec, drop it 00268 if (!use_sim_time) 00269 if (scan_age.toSec() > AGE_THRESHOLD) 00270 { 00271 //ROS_WARN("SCAN SEEMS TOO OLD (%f seconds, %f threshold)", scan_age.toSec(), AGE_THRESHOLD); 00272 ROS_WARN("SCAN SEEMS TOO OLD (%f seconds, %f threshold) scan time: %f , now %f", scan_age.toSec(), AGE_THRESHOLD, scan_in_time.toSec(),ros::Time::now().toSec() ); 00273 scan_callback_mutex.unlock(); 00274 00275 return; 00276 } 00277 00278 count_sc_++; 00279 //ROS_DEBUG("count_sc %i MUTEX LOCKED", count_sc_); 00280 00281 //if (count_sc_ > 10) 00282 //if (count_sc_ > 10) 00283 { 00284 count_sc_ = 0; 00285 00286 tf::StampedTransform base_at_laser; 00287 if (!getTransform(base_at_laser, ODOM_FRAME, "base_link", scan_in_time)) 00288 { 00289 ROS_WARN("Did not get base pose at laser scan time"); 00290 scan_callback_mutex.unlock(); 00291 00292 return; 00293 } 00294 00295 00296 sensor_msgs::PointCloud cloud; 00297 sensor_msgs::PointCloud cloudInMap; 00298 00299 projector_->projectLaser(*scan_in,cloud); 00300 00301 we_have_a_scan = false; 00302 bool gotTransform = false; 00303 00304 if (!listener_->waitForTransform("/map", cloud.header.frame_id, cloud.header.stamp, ros::Duration(0.05))) 00305 { 00306 scan_callback_mutex.unlock(); 00307 ROS_WARN("SnapMapICP no map to cloud transform found MUTEX UNLOCKED"); 00308 return; 00309 } 00310 00311 if (!listener_->waitForTransform("/map", "/base_link", cloud.header.stamp, ros::Duration(0.05))) 00312 { 00313 scan_callback_mutex.unlock(); 00314 ROS_WARN("SnapMapICP no map to base transform found MUTEX UNLOCKED"); 00315 return; 00316 } 00317 00318 00319 while (!gotTransform && (ros::ok())) 00320 { 00321 try 00322 { 00323 gotTransform = true; 00324 listener_->transformPointCloud ("/map",cloud,cloudInMap); 00325 } 00326 catch (...) 00327 { 00328 gotTransform = false; 00329 ROS_WARN("DIDNT GET TRANSFORM IN A"); 00330 } 00331 } 00332 00333 for (size_t k =0; k < cloudInMap.points.size(); k++) 00334 { 00335 cloudInMap.points[k].z = 0; 00336 } 00337 00338 00339 gotTransform = false; 00340 tf::StampedTransform oldPose; 00341 while (!gotTransform && (ros::ok())) 00342 { 00343 try 00344 { 00345 gotTransform = true; 00346 listener_->lookupTransform("/map", "/base_link", 00347 cloud.header.stamp , oldPose); 00348 } 00349 catch (tf::TransformException ex) 00350 { 00351 gotTransform = false; 00352 ROS_WARN("DIDNT GET TRANSFORM IN B"); 00353 } 00354 } 00355 if (we_have_a_map && gotTransform) 00356 { 00357 sensor_msgs::convertPointCloudToPointCloud2(cloudInMap,cloud2); 00358 we_have_a_scan = true; 00359 00360 actScan++; 00361 00362 //pcl::IterativeClosestPointNonLinear<pcl::PointXYZ, pcl::PointXYZ> reg; 00363 pcl::IterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ> reg; 00364 reg.setTransformationEpsilon (1e-6); 00365 // Set the maximum distance between two correspondences (src<->tgt) to 10cm 00366 // Note: adjust this based on the size of your datasets 00367 reg.setMaxCorrespondenceDistance(1.5); 00368 reg.setMaximumIterations (ICP_NUM_ITER); 00369 // Set the point representation 00370 00371 //ros::Time bef = ros::Time::now(); 00372 00373 PointCloudT::Ptr myMapCloud (new PointCloudT()); 00374 PointCloudT::Ptr myScanCloud (new PointCloudT()); 00375 00376 pcl::fromROSMsg(*output_cloud,*myMapCloud); 00377 pcl::fromROSMsg(cloud2,*myScanCloud); 00378 00379 reg.setInputCloud(myScanCloud); 00380 reg.setInputTarget(myMapCloud); 00381 00382 PointCloudT unused; 00383 int i = 0; 00384 00385 reg.align (unused); 00386 00387 const Eigen::Matrix4f &transf = reg.getFinalTransformation(); 00388 tf::Transform t; 00389 matrixAsTransfrom(transf,t); 00390 00391 //ROS_ERROR("proc time %f", (ros::Time::now() - bef).toSec()); 00392 00393 we_have_a_scan_transformed = false; 00394 PointCloudT transformedCloud; 00395 pcl::transformPointCloud (*myScanCloud, transformedCloud, reg.getFinalTransformation()); 00396 00397 double inlier_perc = 0; 00398 { 00399 // count inliers 00400 std::vector<int> nn_indices (1); 00401 std::vector<float> nn_sqr_dists (1); 00402 00403 size_t numinliers = 0; 00404 00405 for (size_t k = 0; k < transformedCloud.points.size(); ++k ) 00406 { 00407 if (mapTree->radiusSearch (transformedCloud.points[k], ICP_INLIER_DIST, nn_indices,nn_sqr_dists, 1) != 0) 00408 numinliers += 1; 00409 } 00410 if (transformedCloud.points.size() > 0) 00411 { 00412 //ROS_INFO("Inliers in dist %f: %zu of %zu percentage %f (%f)", ICP_INLIER_DIST, numinliers, transformedCloud.points.size(), (double) numinliers / (double) transformedCloud.points.size(), ICP_INLIER_THRESHOLD); 00413 inlier_perc = (double) numinliers / (double) transformedCloud.points.size(); 00414 } 00415 } 00416 00417 last_processed_scan = scan_in_time; 00418 00419 pcl::toROSMsg (transformedCloud, cloud2transformed); 00420 we_have_a_scan_transformed = true; 00421 00422 double dist = sqrt((t.getOrigin().x() * t.getOrigin().x()) + (t.getOrigin().y() * t.getOrigin().y())); 00423 double angleDist = t.getRotation().getAngle(); 00424 tf::Vector3 rotAxis = t.getRotation().getAxis(); 00425 t = t * oldPose; 00426 00427 tf::StampedTransform base_after_icp; 00428 if (!getTransform(base_after_icp, ODOM_FRAME, "base_link", ros::Time(0))) 00429 { 00430 ROS_WARN("Did not get base pose at now"); 00431 scan_callback_mutex.unlock(); 00432 00433 return; 00434 } 00435 else 00436 { 00437 tf::Transform rel = base_at_laser.inverseTimes(base_after_icp); 00438 ROS_DEBUG("relative motion of robot while doing icp: %fcm %fdeg", rel.getOrigin().length(), rel.getRotation().getAngle() * 180 / M_PI); 00439 t= t * rel; 00440 } 00441 00442 //ROS_DEBUG("dist %f angleDist %f",dist, angleDist); 00443 00444 //ROS_DEBUG("SCAN_AGE seems to be %f", scan_age.toSec()); 00445 char msg_c_str[2048]; 00446 sprintf(msg_c_str,"INLIERS %f (%f) scan_age %f (%f age_threshold) dist %f angleDist %f axis(%f %f %f) fitting %f (icp_fitness_threshold %f)",inlier_perc, ICP_INLIER_THRESHOLD, scan_age.toSec(), AGE_THRESHOLD ,dist, angleDist, rotAxis.x(), rotAxis.y(), rotAxis.z(),reg.getFitnessScore(), ICP_FITNESS_THRESHOLD ); 00447 std_msgs::String strmsg; 00448 strmsg.data = msg_c_str; 00449 00450 //ROS_DEBUG("%s", msg_c_str); 00451 00452 double cov = POSE_COVARIANCE_TRANS; 00453 00454 //if ((actScan - lastTimeSent > UPDATE_AGE_THRESHOLD) && ((dist > DIST_THRESHOLD) || (angleDist > ANGLE_THRESHOLD)) && (angleDist < ANGLE_UPPER_THRESHOLD)) 00455 // if ( reg.getFitnessScore() <= ICP_FITNESS_THRESHOLD ) 00456 if ((actScan - lastTimeSent > UPDATE_AGE_THRESHOLD) && ((dist > DIST_THRESHOLD) || (angleDist > ANGLE_THRESHOLD)) && (inlier_perc > ICP_INLIER_THRESHOLD) && (angleDist < ANGLE_UPPER_THRESHOLD)) 00457 { 00458 lastTimeSent = actScan; 00459 geometry_msgs::PoseWithCovarianceStamped pose; 00460 pose.header.frame_id = "map"; 00461 pose.pose.pose.position.x = t.getOrigin().x(); 00462 pose.pose.pose.position.y = t.getOrigin().y(); 00463 00464 tf::Quaternion quat = t.getRotation(); 00465 //quat.setRPY(0.0, 0.0, theta); 00466 tf::quaternionTFToMsg(quat,pose.pose.pose.orientation); 00467 float factorPos = 0.03; 00468 float factorRot = 0.1; 00469 pose.pose.covariance[6*0+0] = (cov * cov) * factorPos; 00470 pose.pose.covariance[6*1+1] = (cov * cov) * factorPos; 00471 pose.pose.covariance[6*3+3] = (M_PI/12.0 * M_PI/12.0) * factorRot; 00472 ROS_DEBUG("i %i converged %i SCORE: %f", i, reg.hasConverged (), reg.getFitnessScore() ); 00473 ROS_DEBUG("PUBLISHING A NEW INITIAL POSE dist %f angleDist %f Setting pose: %.3f %.3f [frame=%s]",dist, angleDist , pose.pose.pose.position.x , pose.pose.pose.position.y , pose.header.frame_id.c_str()); 00474 pub_pose.publish(pose); 00475 strmsg.data += " << SENT"; 00476 } 00477 00478 //ROS_INFO("processing time : %f", (ros::Time::now() - time_received).toSec()); 00479 00480 pub_info_.publish(strmsg); 00481 //ROS_DEBUG("map width %i height %i size %i, %s", myMapCloud.width, myMapCloud.height, (int)myMapCloud.points.size(), myMapCloud.header.frame_id.c_str()); 00482 //ROS_DEBUG("scan width %i height %i size %i, %s", myScanCloud.width, myScanCloud.height, (int)myScanCloud.points.size(), myScanCloud.header.frame_id.c_str()); 00483 } 00484 } 00485 scan_callback_mutex.unlock(); 00486 } 00487 00488 00489 ros::Time paramsWereUpdated; 00490 00491 00492 void updateParams() 00493 { 00494 paramsWereUpdated = ros::Time::now(); 00495 // nh.param<std::string>("default_param", default_param, "default_value"); 00496 nh->param<bool>("USE_SIM_TIME", use_sim_time, false); 00497 nh->param<double>("SnapMapICP/icp_fitness_threshold", ICP_FITNESS_THRESHOLD, 100 ); 00498 nh->param<double>("SnapMapICP/age_threshold", AGE_THRESHOLD, 1); 00499 nh->param<double>("SnapMapICP/angle_upper_threshold", ANGLE_UPPER_THRESHOLD, 1); 00500 nh->param<double>("SnapMapICP/angle_threshold", ANGLE_THRESHOLD, 0.01); 00501 nh->param<double>("SnapMapICP/update_age_threshold", UPDATE_AGE_THRESHOLD, 1); 00502 nh->param<double>("SnapMapICP/dist_threshold", DIST_THRESHOLD, 0.01); 00503 nh->param<double>("SnapMapICP/icp_inlier_threshold", ICP_INLIER_THRESHOLD, 0.88); 00504 nh->param<double>("SnapMapICP/icp_inlier_dist", ICP_INLIER_DIST, 0.1); 00505 nh->param<double>("SnapMapICP/icp_num_iter", ICP_NUM_ITER, 250); 00506 nh->param<double>("SnapMapICP/pose_covariance_trans", POSE_COVARIANCE_TRANS, 0.5); 00507 nh->param<double>("SnapMapICP/scan_rate", SCAN_RATE, 2); 00508 if (SCAN_RATE < .001) 00509 SCAN_RATE = .001; 00510 //ROS_DEBUG("PARAM UPDATE"); 00511 00512 } 00513 00514 int main(int argc, char** argv) 00515 { 00516 00517 // Init the ROS node 00518 ros::init(argc, argv, "snapmapicp"); 00519 ros::NodeHandle nh_; 00520 nh = &nh_; 00521 00522 nh->param<std::string>("SnapMapICP/odom_frame", ODOM_FRAME, "/odom_combined"); 00523 nh->param<std::string>("SnapMapICP/base_laser_frame", BASE_LASER_FRAME, "/base_laser_link"); 00524 00525 last_processed_scan = ros::Time::now(); 00526 00527 projector_ = new laser_geometry::LaserProjection(); 00528 tf::TransformListener listener; 00529 listener_ = &listener; 00530 00531 pub_info_ = nh->advertise<std_msgs::String> ("SnapMapICP", 1); 00532 pub_output_ = nh->advertise<sensor_msgs::PointCloud2> ("map_points", 1); 00533 pub_output_scan = nh->advertise<sensor_msgs::PointCloud2> ("scan_points", 1); 00534 pub_output_scan_transformed = nh->advertise<sensor_msgs::PointCloud2> ("scan_points_transformed", 1); 00535 pub_pose = nh->advertise<geometry_msgs::PoseWithCovarianceStamped>("initialpose", 1); 00536 00537 ros::Subscriber subMap = nh_.subscribe("map", 1, mapCallback); 00538 ros::Subscriber subScan = nh_.subscribe("base_scan", 1, scanCallback); 00539 00540 ros::Rate loop_rate(5); 00541 00542 listener_->waitForTransform("/base_link", "/map", 00543 ros::Time(0), ros::Duration(30.0)); 00544 00545 listener_->waitForTransform(BASE_LASER_FRAME, "/map", 00546 ros::Time(0), ros::Duration(30.0)); 00547 00548 ros::AsyncSpinner spinner(1); 00549 spinner.start(); 00550 00551 updateParams(); 00552 00553 ROS_INFO("SnapMapICP running."); 00554 00555 00556 while (ros::ok()) 00557 { 00558 if (actScan > lastScan) 00559 { 00560 lastScan = actScan; 00561 // publish map as a pointcloud2 00562 //if (we_have_a_map) 00563 // pub_output_.publish(Ŕ); 00564 // publish scan as seen as a pointcloud2 00565 //if (we_have_a_scan) 00566 // pub_output_scan.publish(cloud2); 00567 // publish icp transformed scan 00568 if (we_have_a_scan_transformed) 00569 pub_output_scan_transformed.publish(cloud2transformed); 00570 } 00571 loop_rate.sleep(); 00572 ros::spinOnce(); 00573 00574 if (ros::Time::now() - paramsWereUpdated > ros::Duration(1)) 00575 updateParams(); 00576 } 00577 00578 }