00001 #include <fstream>
00002
00003 #include <boost/version.hpp>
00004 #include <boost/thread.hpp>
00005 #if BOOST_VERSION >= 104100
00006 #include <boost/thread/future.hpp>
00007 #endif // BOOST_VERSION >= 104100
00008
00009 #include "ros/ros.h"
00010 #include "ros/console.h"
00011 #include "pointmatcher/PointMatcher.h"
00012 #include "pointmatcher/Timer.h"
00013
00014 #include "nabo/nabo.h"
00015
00016 #include "pointmatcher_ros/point_cloud.h"
00017 #include "pointmatcher_ros/transform.h"
00018 #include "pointmatcher_ros/get_params_from_server.h"
00019 #include "pointmatcher_ros/ros_logger.h"
00020
00021 #include "nav_msgs/Odometry.h"
00022 #include "tf/transform_broadcaster.h"
00023 #include "tf_conversions/tf_eigen.h"
00024 #include "tf/transform_listener.h"
00025 #include "eigen_conversions/eigen_msg.h"
00026
00027
00028 #include "std_msgs/String.h"
00029 #include "std_srvs/Empty.h"
00030 #include "map_msgs/GetPointMap.h"
00031 #include "map_msgs/SaveMap.h"
00032 #include "ethzasl_icp_mapper/LoadMap.h"
00033 #include "ethzasl_icp_mapper/CorrectPose.h"
00034 #include "ethzasl_icp_mapper/SetMode.h"
00035 #include "ethzasl_icp_mapper/GetMode.h"
00036 #include "ethzasl_icp_mapper/GetBoundedMap.h"
00037
00038 using namespace std;
00039 using namespace PointMatcherSupport;
00040
00041 class Mapper
00042 {
00043 typedef PointMatcher<float> PM;
00044 typedef PM::DataPoints DP;
00045 typedef PM::Matches Matches;
00046
00047 typedef typename Nabo::NearestNeighbourSearch<float> NNS;
00048 typedef typename NNS::SearchType NNSearchType;
00049
00050 ros::NodeHandle& n;
00051 ros::NodeHandle& pn;
00052
00053
00054 ros::Subscriber scanSub;
00055 ros::Subscriber cloudSub;
00056
00057
00058 ros::Publisher mapPub;
00059 ros::Publisher outlierPub;
00060 ros::Publisher odomPub;
00061 ros::Publisher odomErrorPub;
00062
00063
00064 ros::ServiceServer getPointMapSrv;
00065 ros::ServiceServer saveMapSrv;
00066 ros::ServiceServer loadMapSrv;
00067 ros::ServiceServer resetSrv;
00068 ros::ServiceServer correctPoseSrv;
00069 ros::ServiceServer setModeSrv;
00070 ros::ServiceServer getModeSrv;
00071 ros::ServiceServer getBoundedMapSrv;
00072
00073
00074 ros::Time mapCreationTime;
00075 ros::Time lastPoinCloudTime;
00076
00077
00078 PM::DataPointsFilters inputFilters;
00079 PM::DataPointsFilters mapPreFilters;
00080 PM::DataPointsFilters mapPostFilters;
00081 PM::DataPoints *mapPointCloud;
00082 PM::ICPSequence icp;
00083 unique_ptr<PM::Transformation> transformation;
00084
00085
00086 #if BOOST_VERSION >= 104100
00087 typedef boost::packaged_task<PM::DataPoints*> MapBuildingTask;
00088 typedef boost::unique_future<PM::DataPoints*> MapBuildingFuture;
00089 boost::thread mapBuildingThread;
00090 MapBuildingTask mapBuildingTask;
00091 MapBuildingFuture mapBuildingFuture;
00092 bool mapBuildingInProgress;
00093 #endif // BOOST_VERSION >= 104100
00094
00095
00096 bool useConstMotionModel;
00097 bool processingNewCloud;
00098 bool localizing;
00099 bool mapping;
00100 int minReadingPointCount;
00101 int minMapPointCount;
00102 int inputQueueSize;
00103 double minOverlap;
00104 double maxOverlapToMerge;
00105 double tfRefreshPeriod;
00106 string odomFrame;
00107 string mapFrame;
00108 string vtkFinalMapName;
00109
00110
00111 PM::TransformationParameters TOdomToMap;
00112 boost::thread publishThread;
00113 boost::mutex publishLock;
00114 ros::Time publishStamp;
00115
00116 tf::TransformListener tfListener;
00117 tf::TransformBroadcaster tfBroadcaster;
00118
00119 const float eps;
00120
00121 public:
00122 Mapper(ros::NodeHandle& n, ros::NodeHandle& pn);
00123 ~Mapper();
00124
00125 protected:
00126 void gotScan(const sensor_msgs::LaserScan& scanMsgIn);
00127 void gotCloud(const sensor_msgs::PointCloud2& cloudMsgIn);
00128 void processCloud(unique_ptr<DP> cloud, const std::string& scannerFrame, const ros::Time& stamp, uint32_t seq);
00129 void processNewMapIfAvailable();
00130 void setMap(DP* newPointCloud);
00131 DP* updateMap(DP* newPointCloud, const PM::TransformationParameters Ticp, bool updateExisting);
00132 void waitForMapBuildingCompleted();
00133
00134 void publishLoop(double publishPeriod);
00135 void publishTransform();
00136
00137
00138 bool getPointMap(map_msgs::GetPointMap::Request &req, map_msgs::GetPointMap::Response &res);
00139 bool saveMap(map_msgs::SaveMap::Request &req, map_msgs::SaveMap::Response &res);
00140 bool loadMap(ethzasl_icp_mapper::LoadMap::Request &req, ethzasl_icp_mapper::LoadMap::Response &res);
00141 bool reset(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res);
00142 bool correctPose(ethzasl_icp_mapper::CorrectPose::Request &req, ethzasl_icp_mapper::CorrectPose::Response &res);
00143 bool setMode(ethzasl_icp_mapper::SetMode::Request &req, ethzasl_icp_mapper::SetMode::Response &res);
00144 bool getMode(ethzasl_icp_mapper::GetMode::Request &req, ethzasl_icp_mapper::GetMode::Response &res);
00145 bool getBoundedMap(ethzasl_icp_mapper::GetBoundedMap::Request &req, ethzasl_icp_mapper::GetBoundedMap::Response &res);
00146 };
00147
00148 Mapper::Mapper(ros::NodeHandle& n, ros::NodeHandle& pn):
00149 n(n),
00150 pn(pn),
00151 mapPointCloud(0),
00152 transformation(PM::get().REG(Transformation).create("RigidTransformation")),
00153 #if BOOST_VERSION >= 104100
00154 mapBuildingInProgress(false),
00155 #endif
00156 useConstMotionModel(getParam<bool>("useConstMotionModel", false)),
00157 processingNewCloud(false),
00158 localizing(getParam<bool>("localizing", true)),
00159 mapping(getParam<bool>("mapping", true)),
00160 minReadingPointCount(getParam<int>("minReadingPointCount", 2000)),
00161 minMapPointCount(getParam<int>("minMapPointCount", 500)),
00162 inputQueueSize(getParam<int>("inputQueueSize", 10)),
00163 minOverlap(getParam<double>("minOverlap", 0.5)),
00164 maxOverlapToMerge(getParam<double>("maxOverlapToMerge", 0.9)),
00165 tfRefreshPeriod(getParam<double>("tfRefreshPeriod", 0.01)),
00166 odomFrame(getParam<string>("odom_frame", "odom")),
00167 mapFrame(getParam<string>("map_frame", "map")),
00168 vtkFinalMapName(getParam<string>("vtkFinalMapName", "finalMap.vtk")),
00169 TOdomToMap(PM::TransformationParameters::Identity(4, 4)),
00170 publishStamp(ros::Time::now()),
00171 tfListener(ros::Duration(30)),
00172 eps(0.0001)
00173 {
00174
00175
00176 if(localizing == false)
00177 mapping = false;
00178 if(mapping == true)
00179 localizing = true;
00180
00181
00182 if (getParam<bool>("useROSLogger", false))
00183 PointMatcherSupport::setLogger(new PointMatcherSupport::ROSLogger);
00184
00185
00186 string configFileName;
00187 if (ros::param::get("~icpConfig", configFileName))
00188 {
00189 ifstream ifs(configFileName.c_str());
00190 if (ifs.good())
00191 {
00192 icp.loadFromYaml(ifs);
00193 }
00194 else
00195 {
00196 ROS_ERROR_STREAM("Cannot load ICP config from YAML file " << configFileName);
00197 icp.setDefault();
00198 }
00199 }
00200 else
00201 {
00202 ROS_INFO_STREAM("No ICP config file given, using default");
00203 icp.setDefault();
00204 }
00205 if (getParam<bool>("useROSLogger", false))
00206 PointMatcherSupport::setLogger(new PointMatcherSupport::ROSLogger);
00207
00208 if (ros::param::get("~inputFiltersConfig", configFileName))
00209 {
00210 ifstream ifs(configFileName.c_str());
00211 if (ifs.good())
00212 {
00213 inputFilters = PM::DataPointsFilters(ifs);
00214 }
00215 else
00216 {
00217 ROS_ERROR_STREAM("Cannot load input filters config from YAML file " << configFileName);
00218 }
00219 }
00220 else
00221 {
00222 ROS_INFO_STREAM("No input filters config file given, not using these filters");
00223 }
00224
00225 if (ros::param::get("~mapPreFiltersConfig", configFileName))
00226 {
00227 ifstream ifs(configFileName.c_str());
00228 if (ifs.good())
00229 {
00230 mapPreFilters = PM::DataPointsFilters(ifs);
00231 }
00232 else
00233 {
00234 ROS_ERROR_STREAM("Cannot load map pre-filters config from YAML file " << configFileName);
00235 }
00236 }
00237 else
00238 {
00239 ROS_INFO_STREAM("No map pre-filters config file given, not using these filters");
00240 }
00241
00242 if (ros::param::get("~mapPostFiltersConfig", configFileName))
00243 {
00244 ifstream ifs(configFileName.c_str());
00245 if (ifs.good())
00246 {
00247 mapPostFilters = PM::DataPointsFilters(ifs);
00248 }
00249 else
00250 {
00251 ROS_ERROR_STREAM("Cannot load map post-filters config from YAML file " << configFileName);
00252 }
00253 }
00254 else
00255 {
00256 ROS_INFO_STREAM("No map post-filters config file given, not using these filters");
00257 }
00258
00259
00260 if (getParam<bool>("subscribe_scan", true))
00261 scanSub = n.subscribe("scan", inputQueueSize, &Mapper::gotScan, this);
00262 if (getParam<bool>("subscribe_cloud", true))
00263 cloudSub = n.subscribe("cloud_in", inputQueueSize, &Mapper::gotCloud, this);
00264 mapPub = n.advertise<sensor_msgs::PointCloud2>("point_map", 2, true);
00265 outlierPub = n.advertise<sensor_msgs::PointCloud2>("outliers", 2, true);
00266 odomPub = n.advertise<nav_msgs::Odometry>("icp_odom", 50, true);
00267 odomErrorPub = n.advertise<nav_msgs::Odometry>("icp_error_odom", 50, true);
00268 getPointMapSrv = n.advertiseService("dynamic_point_map", &Mapper::getPointMap, this);
00269 saveMapSrv = pn.advertiseService("save_map", &Mapper::saveMap, this);
00270 loadMapSrv = pn.advertiseService("load_map", &Mapper::loadMap, this);
00271 resetSrv = pn.advertiseService("reset", &Mapper::reset, this);
00272 correctPoseSrv = pn.advertiseService("correct_pose", &Mapper::correctPose, this);
00273 setModeSrv = pn.advertiseService("set_mode", &Mapper::setMode, this);
00274 getModeSrv = pn.advertiseService("get_mode", &Mapper::getMode, this);
00275 getBoundedMapSrv = pn.advertiseService("get_bounded_map", &Mapper::getBoundedMap, this);
00276
00277
00278 publishThread = boost::thread(boost::bind(&Mapper::publishLoop, this, tfRefreshPeriod));
00279 }
00280
00281 Mapper::~Mapper()
00282 {
00283 #if BOOST_VERSION >= 104100
00284
00285 if (mapBuildingInProgress)
00286 {
00287 mapBuildingFuture.wait();
00288 if (mapBuildingFuture.has_value())
00289 delete mapBuildingFuture.get();
00290 }
00291 #endif // BOOST_VERSION >= 104100
00292
00293 publishThread.join();
00294
00295 if (mapPointCloud)
00296 {
00297 mapPointCloud->save(vtkFinalMapName);
00298 delete mapPointCloud;
00299 }
00300 }
00301
00302 void Mapper::gotScan(const sensor_msgs::LaserScan& scanMsgIn)
00303 {
00304 if(localizing)
00305 {
00306 const ros::Time endScanTime(scanMsgIn.header.stamp + ros::Duration(scanMsgIn.time_increment * (scanMsgIn.ranges.size() - 1)));
00307 unique_ptr<DP> cloud(new DP(PointMatcher_ros::rosMsgToPointMatcherCloud<float>(scanMsgIn, &tfListener, odomFrame)));
00308 processCloud(move(cloud), scanMsgIn.header.frame_id, endScanTime, scanMsgIn.header.seq);
00309 }
00310 }
00311
00312 void Mapper::gotCloud(const sensor_msgs::PointCloud2& cloudMsgIn)
00313 {
00314 if(localizing)
00315 {
00316 unique_ptr<DP> cloud(new DP(PointMatcher_ros::rosMsgToPointMatcherCloud<float>(cloudMsgIn)));
00317 processCloud(move(cloud), cloudMsgIn.header.frame_id, cloudMsgIn.header.stamp, cloudMsgIn.header.seq);
00318 }
00319 }
00320
00321 struct BoolSetter
00322 {
00323 public:
00324 bool toSetValue;
00325 BoolSetter(bool& target, bool toSetValue):
00326 toSetValue(toSetValue),
00327 target(target)
00328 {}
00329 ~BoolSetter()
00330 {
00331 target = toSetValue;
00332 }
00333 protected:
00334 bool& target;
00335 };
00336
00337 void Mapper::processCloud(unique_ptr<DP> newPointCloud, const std::string& scannerFrame, const ros::Time& stamp, uint32_t seq)
00338 {
00339 processingNewCloud = true;
00340 BoolSetter stopProcessingSetter(processingNewCloud, false);
00341
00342
00343 processNewMapIfAvailable();
00344 cerr << "received new map" << endl;
00345
00346
00347 timer t;
00348
00349
00350
00351
00352
00353 const size_t goodCount(newPointCloud->features.cols());
00354 if (goodCount == 0)
00355 {
00356 ROS_ERROR("I found no good points in the cloud");
00357 return;
00358 }
00359
00360
00361 const int dimp1(newPointCloud->features.rows());
00362
00363 if(!(newPointCloud->descriptorExists("stamps_Msec") && newPointCloud->descriptorExists("stamps_sec") && newPointCloud->descriptorExists("stamps_nsec")))
00364 {
00365 const float Msec = round(stamp.sec/10e5);
00366 const float sec = round(Msec*10e5 - stamp.sec);
00367 const float nsec = round(stamp.nsec/10e-10);
00368
00369 const PM::Matrix desc_Msec = PM::Matrix::Constant(1, goodCount, Msec);
00370 const PM::Matrix desc_sec = PM::Matrix::Constant(1, goodCount, sec);
00371 const PM::Matrix desc_nsec = PM::Matrix::Constant(1, goodCount, nsec);
00372 newPointCloud->addDescriptor("stamps_Msec", desc_Msec);
00373 newPointCloud->addDescriptor("stamps_sec", desc_sec);
00374 newPointCloud->addDescriptor("stamps_nsec", desc_nsec);
00375
00376 cout << "Adding time" << endl;
00377
00378 }
00379
00380 ROS_INFO("Processing new point cloud");
00381 {
00382 timer t;
00383
00384
00385 inputFilters.apply(*newPointCloud);
00386
00387 ROS_INFO_STREAM("Input filters took " << t.elapsed() << " [s]");
00388 }
00389
00390 string reason;
00391
00392 if(!icp.hasMap())
00393 {
00394
00395 publishLock.lock();
00396 TOdomToMap = PM::TransformationParameters::Identity(dimp1, dimp1);
00397 publishLock.unlock();
00398 }
00399
00400
00401
00402 PM::TransformationParameters TOdomToScanner;
00403 try
00404 {
00405 TOdomToScanner = PointMatcher_ros::eigenMatrixToDim<float>(
00406 PointMatcher_ros::transformListenerToEigenMatrix<float>(
00407 tfListener,
00408 scannerFrame,
00409 odomFrame,
00410 stamp
00411 ), dimp1);
00412 }
00413 catch(tf::ExtrapolationException e)
00414 {
00415 ROS_ERROR_STREAM("Extrapolation Exception. stamp = "<< stamp << " now = " << ros::Time::now() << " delta = " << ros::Time::now() - stamp);
00416 return;
00417 }
00418
00419
00420 ROS_DEBUG_STREAM("TOdomToScanner(" << odomFrame<< " to " << scannerFrame << "):\n" << TOdomToScanner);
00421 ROS_DEBUG_STREAM("TOdomToMap(" << odomFrame<< " to " << mapFrame << "):\n" << TOdomToMap);
00422
00423 const PM::TransformationParameters TscannerToMap = TOdomToMap * TOdomToScanner.inverse();
00424 ROS_DEBUG_STREAM("TscannerToMap (" << scannerFrame << " to " << mapFrame << "):\n" << TscannerToMap);
00425
00426
00427 const int ptsCount = newPointCloud->features.cols();
00428 if(ptsCount < minReadingPointCount)
00429 {
00430 ROS_ERROR_STREAM("Not enough points in newPointCloud: only " << ptsCount << " pts.");
00431 return;
00432 }
00433
00434
00435 if(!icp.hasMap())
00436 {
00437 ROS_INFO_STREAM("Creating an initial map");
00438 mapCreationTime = stamp;
00439 setMap(updateMap(newPointCloud.release(), TscannerToMap, false));
00440
00441 return;
00442 }
00443
00444
00445 if (newPointCloud->features.rows() != icp.getInternalMap().features.rows())
00446 {
00447 ROS_ERROR_STREAM("Dimensionality missmatch: incoming cloud is " << newPointCloud->features.rows()-1 << " while map is " << icp.getInternalMap().features.rows()-1);
00448 return;
00449 }
00450
00451 try
00452 {
00453
00454 PM::TransformationParameters Ticp;
00455 Ticp = icp(*newPointCloud, TscannerToMap);
00456
00457 ROS_DEBUG_STREAM("Ticp:\n" << Ticp);
00458
00459
00460 const double estimatedOverlap = icp.errorMinimizer->getOverlap();
00461 ROS_INFO_STREAM("Overlap: " << estimatedOverlap);
00462 if (estimatedOverlap < minOverlap)
00463 {
00464 ROS_ERROR_STREAM("Estimated overlap too small, ignoring ICP correction!");
00465 return;
00466 }
00467
00468
00469 publishStamp = stamp;
00470 publishLock.lock();
00471 TOdomToMap = Ticp * TOdomToScanner;
00472
00473 tfBroadcaster.sendTransform(PointMatcher_ros::eigenMatrixToStampedTransform<float>(TOdomToMap, mapFrame, odomFrame, stamp));
00474 publishLock.unlock();
00475 processingNewCloud = false;
00476
00477 ROS_DEBUG_STREAM("TOdomToMap:\n" << TOdomToMap);
00478
00479
00480 if (odomPub.getNumSubscribers())
00481 odomPub.publish(PointMatcher_ros::eigenMatrixToOdomMsg<float>(Ticp, mapFrame, stamp));
00482
00483
00484 if (odomErrorPub.getNumSubscribers())
00485 odomErrorPub.publish(PointMatcher_ros::eigenMatrixToOdomMsg<float>(TOdomToMap, mapFrame, stamp));
00486
00487
00488
00489
00490 if (
00491 mapping &&
00492 ((estimatedOverlap < maxOverlapToMerge) || (icp.getInternalMap().features.cols() < minMapPointCount)) &&
00493 #if BOOST_VERSION >= 104100
00494 (!mapBuildingInProgress)
00495 #else
00496 true
00497 #endif
00498 )
00499 {
00500 cout << "map Creation..." << endl;
00501
00502 mapCreationTime = stamp;
00503 #if BOOST_VERSION >= 104100
00504 ROS_INFO("Adding new points to the map in background");
00505 mapBuildingTask = MapBuildingTask(boost::bind(&Mapper::updateMap, this, newPointCloud.release(), Ticp, true));
00506 mapBuildingFuture = mapBuildingTask.get_future();
00507 mapBuildingThread = boost::thread(boost::move(boost::ref(mapBuildingTask)));
00508 mapBuildingInProgress = true;
00509 #else // BOOST_VERSION >= 104100
00510 ROS_INFO("Adding new points to the map");
00511 setMap(updateMap( newPointCloud.release(), Ticp, true));
00512 #endif // BOOST_VERSION >= 104100
00513 }
00514 }
00515 catch (PM::ConvergenceError error)
00516 {
00517 ROS_ERROR_STREAM("ICP failed to converge: " << error.what());
00518 return;
00519 }
00520
00521
00522 int realTimeRatio = 100*t.elapsed() / (stamp.toSec()-lastPoinCloudTime.toSec());
00523 ROS_INFO_STREAM("[TIME] Total ICP took: " << t.elapsed() << " [s]");
00524 if(realTimeRatio < 80)
00525 ROS_INFO_STREAM("[TIME] Real-time capability: " << realTimeRatio << "%");
00526 else
00527 ROS_WARN_STREAM("[TIME] Real-time capability: " << realTimeRatio << "%");
00528
00529 lastPoinCloudTime = stamp;
00530 }
00531
00532 void Mapper::processNewMapIfAvailable()
00533 {
00534 #if BOOST_VERSION >= 104100
00535 if (mapBuildingInProgress && mapBuildingFuture.has_value())
00536 {
00537 ROS_INFO_STREAM("New map available");
00538 setMap(mapBuildingFuture.get());
00539 mapBuildingInProgress = false;
00540 }
00541 #endif // BOOST_VERSION >= 104100
00542 }
00543
00544 void Mapper::setMap(DP* newPointCloud)
00545 {
00546
00547 if (mapPointCloud)
00548 delete mapPointCloud;
00549
00550
00551 mapPointCloud = newPointCloud;
00552 cerr << "copying map to ICP" << endl;
00553 icp.setMap(*mapPointCloud);
00554
00555
00556 cerr << "publishing map" << endl;
00557
00558
00559 if (mapPub.getNumSubscribers())
00560 mapPub.publish(PointMatcher_ros::pointMatcherCloudToRosMsg<float>(*mapPointCloud, mapFrame, mapCreationTime));
00561 }
00562
00563 Mapper::DP* Mapper::updateMap(DP* newPointCloud, const PM::TransformationParameters Ticp, bool updateExisting)
00564 {
00565 timer t;
00566
00567
00568 const float priorStatic = 0.8;
00569 const float priorDyn = 0.2;
00570
00571
00572 if(newPointCloud->descriptorExists("observedTime") == false)
00573 {
00574
00575 newPointCloud->addDescriptor("observedTime", PM::Matrix::Constant(1, newPointCloud->features.cols(), priorStatic));
00576 }
00577
00578 if(newPointCloud->descriptorExists("unobservedTime") == false)
00579 {
00580
00581 newPointCloud->addDescriptor("unobservedTime", PM::Matrix::Constant(1, newPointCloud->features.cols(), priorDyn));
00582 }
00583
00584 if(newPointCloud->descriptorExists("dynamic_ratio") == false)
00585 {
00586 newPointCloud->addDescriptor("dynamic_ratio", PM::Matrix::Zero(1, newPointCloud->features.cols()));
00587 }
00588
00589 if (!updateExisting)
00590 {
00591
00592 cout << "Jumping map creation" << endl;
00593 *newPointCloud = transformation->compute(*newPointCloud, Ticp);
00594 mapPostFilters.apply(*newPointCloud);
00595 return newPointCloud;
00596 }
00597
00598
00599
00600 const int readPtsCount(newPointCloud->features.cols());
00601 const int mapPtsCount(mapPointCloud->features.cols());
00602
00603
00604 PM::Matrix radius_reading = newPointCloud->features.topRows(3).colwise().norm();
00605
00606 PM::Matrix angles_reading(2, readPtsCount);
00607
00608
00609 for(int i=0; i<readPtsCount; i++)
00610 {
00611 const float ratio = newPointCloud->features(2,i)/radius_reading(0,i);
00612
00613
00614
00615 angles_reading(0,i) = acos(ratio);
00616 angles_reading(1,i) = atan2(newPointCloud->features(1,i), newPointCloud->features(0,i));
00617 }
00618
00619 std::shared_ptr<NNS> featureNNS;
00620 featureNNS.reset( NNS::create(angles_reading));
00621
00622
00623
00624 DP mapLocalFrame = transformation->compute(*mapPointCloud, Ticp.inverse());
00625
00626
00627
00628 const float sensorMaxRange = 80.0;
00629 PM::Matrix globalId(1, mapPtsCount);
00630
00631 int mapCutPtsCount = 0;
00632 DP mapLocalFrameCut(mapLocalFrame.createSimilarEmpty());
00633 for (int i = 0; i < mapPtsCount; i++)
00634 {
00635 if (mapLocalFrame.features.col(i).head(3).norm() < sensorMaxRange)
00636 {
00637 mapLocalFrameCut.setColFrom(mapCutPtsCount, mapLocalFrame, i);
00638 globalId(0,mapCutPtsCount) = i;
00639 mapCutPtsCount++;
00640 }
00641 }
00642
00643 mapLocalFrameCut.conservativeResize(mapCutPtsCount);
00644
00645
00646
00647
00648
00649
00650
00651
00652 PM::Matrix radius_map = mapLocalFrameCut.features.topRows(3).colwise().norm();
00653
00654 PM::Matrix angles_map(2, mapCutPtsCount);
00655
00656
00657 for(int i=0; i<mapCutPtsCount; i++)
00658 {
00659 const float ratio = mapLocalFrameCut.features(2,i)/radius_map(0,i);
00660
00661
00662
00663 angles_map(0,i) = acos(ratio);
00664
00665 angles_map(1,i) = atan2(mapLocalFrameCut.features(1,i), mapLocalFrameCut.features(0,i));
00666 }
00667
00668
00669 Matches::Dists dists(1,mapCutPtsCount);
00670 Matches::Ids ids(1,mapCutPtsCount);
00671
00672
00673 const float maxAngle = 0.04;
00674 featureNNS->knn(angles_map, ids, dists, 1, 0, NNS::ALLOW_SELF_MATCH, maxAngle);
00675
00676
00677 DP::View viewOn_normals_overlap = newPointCloud->getDescriptorViewByName("normals");
00678 DP::View viewOn_obsDir_overlap = newPointCloud->getDescriptorViewByName("observationDirections");
00679 DP::View viewOn_Msec_overlap = newPointCloud->getDescriptorViewByName("stamps_Msec");
00680 DP::View viewOn_sec_overlap = newPointCloud->getDescriptorViewByName("stamps_sec");
00681 DP::View viewOn_nsec_overlap = newPointCloud->getDescriptorViewByName("stamps_nsec");
00682
00683 DP::View viewOnObservedTime = mapPointCloud->getDescriptorViewByName("observedTime");
00684 DP::View viewOnUnobservedTime = mapPointCloud->getDescriptorViewByName("unobservedTime");
00685 DP::View viewOnDynamicRatio = mapPointCloud->getDescriptorViewByName("dynamic_ratio");
00686
00687 DP::View viewOn_normals_map = mapPointCloud->getDescriptorViewByName("normals");
00688 DP::View viewOn_Msec_map = mapPointCloud->getDescriptorViewByName("stamps_Msec");
00689 DP::View viewOn_sec_map = mapPointCloud->getDescriptorViewByName("stamps_sec");
00690 DP::View viewOn_nsec_map = mapPointCloud->getDescriptorViewByName("stamps_nsec");
00691
00692
00693 const float eps_a = 0.2;
00694 const float eps_d = 0.1;
00695 const float alpha = 0.99;
00696 const float beta = 0.99;
00697
00698
00699 viewOnDynamicRatio = PM::Matrix::Zero(1, mapPtsCount);
00700 for(int i=0; i < mapCutPtsCount; i++)
00701 {
00702 if(dists(i) != numeric_limits<float>::infinity())
00703 {
00704 const int readId = ids(0,i);
00705 const int mapId = globalId(0,i);
00706
00707
00708 const Eigen::Vector3f readPt = newPointCloud->features.col(readId).head(3);
00709 const Eigen::Vector3f mapPt = mapLocalFrameCut.features.col(i).head(3);
00710 const Eigen::Vector3f mapPt_n = mapPt.normalized();
00711 const float delta = (readPt - mapPt).norm();
00712 const float d_max = eps_a * readPt.norm();
00713
00714
00715
00716
00717
00718 const Eigen::Vector3f normal_map = viewOn_normals_map.col(mapId);
00719 const Eigen::Vector3f normal_read = viewOn_normals_overlap.col(readId);
00720 const Eigen::Vector3f obsDir = viewOn_obsDir_overlap.col(readId);
00721
00722
00723
00724
00725 const float w_v = eps + (1 - eps)*fabs(normal_map.dot(mapPt_n));
00726
00727 const float w_d1 = eps + (1 - eps)*(1 - sqrt(dists(i))/maxAngle);
00728
00729
00730 const float offset = delta - eps_d;
00731 float w_d2 = 1;
00732 if(delta < eps_d || mapPt.norm() > readPt.norm())
00733 {
00734 w_d2 = eps;
00735 }
00736 else
00737 {
00738 if (offset < d_max)
00739 {
00740 w_d2 = eps + (1 - eps )*offset/d_max;
00741 }
00742 }
00743
00744 float w_p2 = eps;
00745 if(delta < eps_d)
00746 {
00747 w_p2 = 1;
00748 }
00749 else
00750 {
00751 if(offset < d_max)
00752 {
00753 w_p2 = eps + (1 - eps)*(1 - offset/d_max);
00754 }
00755 }
00756
00757
00758
00759
00760
00761 if((readPt.norm() + eps_d + d_max) >= mapPt.norm())
00762 {
00763 const float lastDyn = viewOnUnobservedTime(0,mapId);
00764 const float lastStatic = viewOnObservedTime(0, mapId);
00765
00766 const float c1 = (1 - (w_v*(1 - w_d1)));
00767 const float c2 = w_v*(1 - w_d1);
00768
00769
00770
00771
00772
00773
00774
00775
00776
00777 if(lastDyn < 0.9)
00778 {
00779 viewOnUnobservedTime(0,mapId) = c1*lastDyn + c2*w_d2*((1 - alpha)*lastStatic + beta*lastDyn);
00780 viewOnObservedTime(0, mapId) = c1*lastStatic + c2*w_p2*(alpha*lastStatic + (1 - beta)*lastDyn);
00781 }
00782 else
00783 {
00784 viewOnObservedTime(0,mapId) = eps;
00785 viewOnUnobservedTime(0,mapId) = 1-eps;
00786 }
00787
00788
00789
00790
00791 const float sumZ = viewOnUnobservedTime(0,mapId) + viewOnObservedTime(0, mapId);
00792 assert(sumZ >= eps);
00793
00794 viewOnUnobservedTime(0,mapId) /= sumZ;
00795 viewOnObservedTime(0,mapId) /= sumZ;
00796
00797
00798 viewOnDynamicRatio(0,mapId) = w_d2;
00799
00800
00801
00802
00803
00804
00805
00806
00807
00808
00809
00810 viewOn_Msec_map(0,mapId) = viewOn_Msec_overlap(0,readId);
00811 viewOn_sec_map(0,mapId) = viewOn_sec_overlap(0,readId);
00812 viewOn_nsec_map(0,mapId) = viewOn_nsec_overlap(0,readId);
00813 }
00814
00815
00816 }
00817 }
00818
00819
00820
00821
00822
00823
00824
00825
00826
00827 DP tmp_map = mapLocalFrameCut;
00828 tmp_map.concatenate(*newPointCloud);
00829
00830
00831
00832
00833 cout << "build first kdtree with " << tmp_map.features.cols() << endl;
00834
00835 featureNNS.reset( NNS::create(tmp_map.features, tmp_map.features.rows() - 1, NNS::KDTREE_LINEAR_HEAP, NNS::TOUCH_STATISTICS));
00836
00837 PM::Matches matches_overlap(
00838 Matches::Dists(1, readPtsCount),
00839 Matches::Ids(1, readPtsCount)
00840 );
00841
00842 featureNNS->knn(newPointCloud->features, matches_overlap.ids, matches_overlap.dists, 1, 0);
00843
00844
00845 DP overlap(newPointCloud->createSimilarEmpty());
00846 DP no_overlap(newPointCloud->createSimilarEmpty());
00847
00848
00849
00850
00851 const float maxDist = pow(0.3, 2);
00852
00853
00854 int ptsOut = 0;
00855 int ptsIn = 0;
00856 for (int i = 0; i < readPtsCount; ++i)
00857 {
00858 if (matches_overlap.dists(i) > maxDist)
00859 {
00860 no_overlap.setColFrom(ptsOut, *newPointCloud, i);
00861 ptsOut++;
00862 }
00863 else
00864 {
00865 overlap.setColFrom(ptsIn, *newPointCloud, i);
00866 ptsIn++;
00867 }
00868 }
00869
00870 no_overlap.conservativeResize(ptsOut);
00871 overlap.conservativeResize(ptsIn);
00872
00873 cout << "ptsOut=" << ptsOut << ", ptsIn=" << ptsIn << endl;
00874
00875
00876
00877
00878
00879
00880
00881
00882
00883 no_overlap.addDescriptor("observedTime", PM::Matrix::Constant(1, no_overlap.features.cols(), priorStatic));
00884
00885 no_overlap.addDescriptor("unobservedTime", PM::Matrix::Constant(1, no_overlap.features.cols(), priorDyn));
00886
00887 no_overlap.addDescriptor("dynamic_ratio", PM::Matrix::Zero(1, no_overlap.features.cols()));
00888
00889
00890 *newPointCloud = no_overlap;
00891
00892
00893
00894
00895 *newPointCloud = transformation->compute(*newPointCloud, Ticp);
00896
00897
00898
00899
00900
00901 newPointCloud->concatenate(*mapPointCloud);
00902 mapPostFilters.apply(*newPointCloud);
00903
00904 cout << "... end map creation" << endl;
00905 ROS_INFO_STREAM("[TIME] New map available (" << newPointCloud->features.cols() << " pts), update took " << t.elapsed() << " [s]");
00906
00907 return newPointCloud;
00908 }
00909
00910 void Mapper::waitForMapBuildingCompleted()
00911 {
00912 #if BOOST_VERSION >= 104100
00913 if (mapBuildingInProgress)
00914 {
00915
00916 mapBuildingFuture.wait();
00917 mapBuildingInProgress = false;
00918 }
00919 #endif // BOOST_VERSION >= 104100
00920 }
00921
00922 void Mapper::publishLoop(double publishPeriod)
00923 {
00924 if(publishPeriod == 0)
00925 return;
00926 ros::Rate r(1.0 / publishPeriod);
00927 while(ros::ok())
00928 {
00929 publishTransform();
00930 r.sleep();
00931 }
00932 }
00933
00934 void Mapper::publishTransform()
00935 {
00936 if(processingNewCloud == false)
00937 {
00938 publishLock.lock();
00939
00940 tfBroadcaster.sendTransform(PointMatcher_ros::eigenMatrixToStampedTransform<float>(TOdomToMap, mapFrame, odomFrame, ros::Time::now()));
00941 publishLock.unlock();
00942 }
00943 }
00944
00945 bool Mapper::getPointMap(map_msgs::GetPointMap::Request &req, map_msgs::GetPointMap::Response &res)
00946 {
00947 if (!mapPointCloud)
00948 return false;
00949
00950
00951 res.map = PointMatcher_ros::pointMatcherCloudToRosMsg<float>(*mapPointCloud, mapFrame, ros::Time::now());
00952 return true;
00953 }
00954
00955 bool Mapper::saveMap(map_msgs::SaveMap::Request &req, map_msgs::SaveMap::Response &res)
00956 {
00957 if (!mapPointCloud)
00958 return false;
00959
00960 try
00961 {
00962 mapPointCloud->save(req.filename.data);
00963 }
00964 catch (const std::runtime_error& e)
00965 {
00966 ROS_ERROR_STREAM("Unable to save: " << e.what());
00967 return false;
00968 }
00969
00970 ROS_INFO_STREAM("Map saved at " << req.filename.data << "with " << mapPointCloud->features.cols() << " points.");
00971 return true;
00972 }
00973
00974 bool Mapper::loadMap(ethzasl_icp_mapper::LoadMap::Request &req, ethzasl_icp_mapper::LoadMap::Response &res)
00975 {
00976 waitForMapBuildingCompleted();
00977
00978 DP* cloud(new DP(DP::load(req.filename.data)));
00979
00980 const int dim = cloud->features.rows();
00981 const int nbPts = cloud->features.cols();
00982 ROS_INFO_STREAM("Loading " << dim-1 << "D point cloud (" << req.filename.data << ") with " << nbPts << " points.");
00983
00984 publishLock.lock();
00985 TOdomToMap = PM::TransformationParameters::Identity(dim,dim);
00986 publishLock.unlock();
00987
00988 setMap(cloud);
00989
00990 return true;
00991 }
00992
00993 bool Mapper::reset(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
00994 {
00995 waitForMapBuildingCompleted();
00996
00997
00998 publishLock.lock();
00999 TOdomToMap = PM::TransformationParameters::Identity(4,4);
01000 publishLock.unlock();
01001
01002 icp.clearMap();
01003
01004 return true;
01005 }
01006
01007 bool Mapper::correctPose(ethzasl_icp_mapper::CorrectPose::Request &req, ethzasl_icp_mapper::CorrectPose::Response &res)
01008 {
01009 publishLock.lock();
01010 TOdomToMap = PointMatcher_ros::odomMsgToEigenMatrix<float>(req.odom);
01011 tfBroadcaster.sendTransform(PointMatcher_ros::eigenMatrixToStampedTransform<float>(TOdomToMap, mapFrame, odomFrame, ros::Time::now()));
01012 publishLock.unlock();
01013
01014 return true;
01015 }
01016
01017 bool Mapper::setMode(ethzasl_icp_mapper::SetMode::Request &req, ethzasl_icp_mapper::SetMode::Response &res)
01018 {
01019
01020 if(req.localize == false && req.map == true)
01021 return false;
01022
01023 localizing = req.localize;
01024 mapping = req.map;
01025
01026 return true;
01027 }
01028
01029 bool Mapper::getMode(ethzasl_icp_mapper::GetMode::Request &req, ethzasl_icp_mapper::GetMode::Response &res)
01030 {
01031 res.localize = localizing;
01032 res.map = mapping;
01033 return true;
01034 }
01035
01036
01037
01038 bool Mapper::getBoundedMap(ethzasl_icp_mapper::GetBoundedMap::Request &req, ethzasl_icp_mapper::GetBoundedMap::Response &res)
01039 {
01040 if (!mapPointCloud)
01041 return false;
01042
01043 const float max_x = req.topRightCorner.x;
01044 const float max_y = req.topRightCorner.y;
01045 const float max_z = req.topRightCorner.z;
01046
01047 const float min_x = req.bottomLeftCorner.x;
01048 const float min_y = req.bottomLeftCorner.y;
01049 const float min_z = req.bottomLeftCorner.z;
01050
01051 cerr << "min [" << min_x << ", " << min_y << ", " << min_z << "] " << endl;
01052 cerr << "max [" << max_x << ", " << max_y << ", " << max_z << "] " << endl;
01053
01054
01055
01056 tf::StampedTransform stampedTr;
01057
01058 Eigen::Affine3d eigenTr;
01059 tf::poseMsgToEigen(req.mapCenter, eigenTr);
01060 Eigen::MatrixXf T = eigenTr.matrix().inverse().cast<float>();
01061
01062
01063 cerr << "T:" << endl << T << endl;
01064 T = transformation->correctParameters(T);
01065
01066
01067
01068 const DP centeredPointCloud = transformation->compute(*mapPointCloud, T);
01069 DP cutPointCloud = centeredPointCloud.createSimilarEmpty();
01070
01071 cerr << centeredPointCloud.features.topLeftCorner(3, 10) << endl;
01072 cerr << T << endl;
01073
01074 int newPtCount = 0;
01075 for(int i=0; i < centeredPointCloud.features.cols(); i++)
01076 {
01077 const float x = centeredPointCloud.features(0,i);
01078 const float y = centeredPointCloud.features(1,i);
01079 const float z = centeredPointCloud.features(2,i);
01080
01081 if(x < max_x && x > min_x &&
01082 y < max_y && y > min_y &&
01083 z < max_z && z > min_z )
01084 {
01085 cutPointCloud.setColFrom(newPtCount, centeredPointCloud, i);
01086 newPtCount++;
01087 }
01088 }
01089
01090 cerr << "Extract " << newPtCount << " points from the map" << endl;
01091
01092 cutPointCloud.conservativeResize(newPtCount);
01093 cutPointCloud = transformation->compute(cutPointCloud, T.inverse());
01094
01095
01096
01097 res.boundedMap = PointMatcher_ros::pointMatcherCloudToRosMsg<float>(cutPointCloud, mapFrame, ros::Time::now());
01098 return true;
01099 }
01100
01101
01102 int main(int argc, char **argv)
01103 {
01104 ros::init(argc, argv, "mapper");
01105 ros::NodeHandle n;
01106 ros::NodeHandle pn("~");
01107 Mapper mapper(n, pn);
01108 ros::spin();
01109
01110 return 0;
01111 }