mrpt_localization.cpp
Go to the documentation of this file.
00001 /***********************************************************************************
00002  * Revised BSD License *
00003  * Copyright (c) 2014, Markus Bader <markus.bader@tuwien.ac.at> *
00004  * All rights reserved. *
00005  *                                                                                 *
00006  * Redistribution and use in source and binary forms, with or without *
00007  * modification, are permitted provided that the following conditions are met: *
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 Vienna University of Technology nor the *
00014  *       names of its contributors may be used to endorse or promote products *
00015  *       derived from this software without specific prior written permission. *
00016  *                                                                                 *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  *AND *
00019  * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00020  **
00021  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE *
00022  * DISCLAIMED. IN NO EVENT SHALL Markus Bader BE LIABLE FOR ANY *
00023  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES *
00024  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025  **
00026  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND *
00027  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT *
00028  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00029  **
00030  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00031  **                       *
00032  ***********************************************************************************/
00033 
00034 #include <mrpt_localization/mrpt_localization.h>
00035 #include <mrpt_localization/mrpt_localization_defaults.h>
00036 
00037 #include <mrpt_bridge/map.h>
00038 #include <mrpt/maps/COccupancyGridMap2D.h>
00039 #include <mrpt/maps/CSimplePointsMap.h>
00040 using mrpt::maps::COccupancyGridMap2D;
00041 using mrpt::maps::CSimplePointsMap;
00042 
00043 #include <mrpt/system/filesystem.h>
00044 #include <mrpt/opengl/CEllipsoid.h>
00045 #include <mrpt/opengl/CPointCloud.h>
00046 
00047 #include <thread>
00048 #include <chrono>
00049 
00050 using namespace mrpt;
00051 using namespace mrpt::slam;
00052 using namespace mrpt::opengl;
00053 using namespace mrpt::gui;
00054 using namespace mrpt::math;
00055 using namespace mrpt::system;
00056 using namespace mrpt::bayes;
00057 using namespace mrpt::poses;
00058 using namespace std;
00059 
00060 #include <mrpt/version.h>
00061 using namespace mrpt::maps;
00062 using namespace mrpt::obs;
00063 
00064 #if MRPT_VERSION >= 0x199
00065 using namespace mrpt::img;
00066 using namespace mrpt::config;
00067 #else
00068 using namespace mrpt::utils;
00069 #endif
00070 
00071 PFLocalization::~PFLocalization() {}
00072 PFLocalization::PFLocalization(Parameters* param)
00073         : PFLocalizationCore(), param_(param)
00074 {
00075 }
00076 
00077 void PFLocalization::init()
00078 {
00079         log_info("ini_file ready %s", param_->ini_file.c_str());
00080         ASSERT_FILE_EXISTS_(param_->ini_file);
00081         log_info("ASSERT_FILE_EXISTS_ %s", param_->ini_file.c_str());
00082         CConfigFile ini_file;
00083         ini_file.setFileName(param_->ini_file);
00084         log_info("CConfigFile %s", param_->ini_file.c_str());
00085 
00086         std::vector<int>
00087                 particles_count;  // Number of initial particles (if size>1, run
00088         // the experiments N times)
00089 
00090         // Load configuration:
00091         // -----------------------------------------
00092         string iniSectionName("LocalizationExperiment");
00093         update_counter_ = 0;
00094 
00095         // Mandatory entries:
00096         ini_file.read_vector(
00097                 iniSectionName, "particles_count", std::vector<int>(1, 0),
00098                 particles_count,
00099                 /*Fail if not found*/ true);
00100 
00101         if (param_->map_file.empty())
00102         {
00103                 param_->map_file = ini_file.read_string(iniSectionName, "map_file", "");
00104         }
00105 
00106         // Non-mandatory entries:
00107         SCENE3D_FREQ_ = ini_file.read_int(iniSectionName, "3DSceneFrequency", 10);
00108         SCENE3D_FOLLOW_ =
00109                 ini_file.read_bool(iniSectionName, "3DSceneFollowRobot", true);
00110 
00111         SHOW_PROGRESS_3D_REAL_TIME_ =
00112                 ini_file.read_bool(iniSectionName, "SHOW_PROGRESS_3D_REAL_TIME", false);
00113         SHOW_PROGRESS_3D_REAL_TIME_DELAY_MS_ = ini_file.read_int(
00114                 iniSectionName, "SHOW_PROGRESS_3D_REAL_TIME_DELAY_MS", 1);
00115 
00116 #if !MRPT_HAS_WXWIDGETS
00117         SHOW_PROGRESS_3D_REAL_TIME_ = false;
00118 #endif
00119 
00120         // Default odometry uncertainty parameters in "odom_params_default_"
00121         // depending on how fast the robot moves, etc...
00122         //  Only used for observations-only rawlogs:
00123         motion_model_default_options_.modelSelection =
00124                 CActionRobotMovement2D::mmGaussian;
00125 
00126         motion_model_default_options_.gaussianModel.minStdXY =
00127                 ini_file.read_double("DummyOdometryParams", "minStdXY", 0.04);
00128         motion_model_default_options_.gaussianModel.minStdPHI = DEG2RAD(
00129                 ini_file.read_double("DefaultOdometryParams", "minStdPHI", 2.0));
00130 
00131         // Read initial particles distribution; fail if any parameter is not found
00132         init_PDF_mode =
00133                 ini_file.read_bool(iniSectionName, "init_PDF_mode", false, true);
00134         init_PDF_min_x =
00135                 ini_file.read_float(iniSectionName, "init_PDF_min_x", 0, true);
00136         init_PDF_max_x =
00137                 ini_file.read_float(iniSectionName, "init_PDF_max_x", 0, true);
00138         init_PDF_min_y =
00139                 ini_file.read_float(iniSectionName, "init_PDF_min_y", 0, true);
00140         init_PDF_max_y =
00141                 ini_file.read_float(iniSectionName, "init_PDF_max_y", 0, true);
00142         float min_phi = DEG2RAD(
00143                 ini_file.read_float(iniSectionName, "init_PDF_min_phi_deg", -180));
00144         float max_phi = DEG2RAD(
00145                 ini_file.read_float(iniSectionName, "init_PDF_max_phi_deg", 180));
00146         mrpt::poses::CPose2D p;
00147         mrpt::math::CMatrixDouble33 cov;
00148         cov(0, 0) = fabs(init_PDF_max_x - init_PDF_min_x);
00149         cov(1, 1) = fabs(init_PDF_max_y - init_PDF_min_y);
00150         cov(2, 2) =
00151                 min_phi < max_phi ? max_phi - min_phi : (max_phi + 2 * M_PI) - min_phi;
00152         p.x() = init_PDF_min_x + cov(0, 0) / 2.0;
00153         p.y() = init_PDF_min_y + cov(1, 1) / 2.0;
00154         p.phi() = min_phi + cov(2, 2) / 2.0;
00155         log_debug(
00156                 "----------- phi: %4.3f: %4.3f <-> %4.3f, %4.3f\n", p.phi(), min_phi,
00157                 max_phi, cov(2, 2));
00158         initial_pose_ = mrpt::poses::CPosePDFGaussian(p, cov);
00159         state_ = INIT;
00160 
00161         configureFilter(ini_file);
00162         // Metric map options:
00163 
00164         if (!mrpt_bridge::MapHdl::loadMap(
00165                         metric_map_, ini_file, param_->map_file, "metricMap",
00166                         param_->debug))
00167         {
00168                 waitForMap();
00169         }
00170 
00171         initial_particle_count_ = *particles_count.begin();
00172 
00173         if (param_->gui_mrpt) init3DDebug();
00174 }
00175 
00176 void PFLocalization::configureFilter(const CConfigFile& _configFile)
00177 {
00178         // PF-algorithm Options:
00179         // ---------------------------
00180         CParticleFilter::TParticleFilterOptions pfOptions;
00181         pfOptions.loadFromConfigFile(_configFile, "PF_options");
00182         pfOptions.dumpToConsole();
00183 
00184         // PDF Options:
00185         // ------------------
00186         TMonteCarloLocalizationParams pdfPredictionOptions;
00187         pdfPredictionOptions.KLD_params.loadFromConfigFile(
00188                 _configFile, "KLD_options");
00189 
00190         pdf_.clear();
00191 
00192         // PDF Options:
00193         pdf_.options = pdfPredictionOptions;
00194 
00195         pdf_.options.metricMap = &metric_map_;
00196 
00197         // Create the PF object:
00198         pf_.m_options = pfOptions;
00199 }
00200 
00201 void PFLocalization::init3DDebug()
00202 {
00203         log_info("init3DDebug");
00204         if (!SHOW_PROGRESS_3D_REAL_TIME_) return;
00205         if (!win3D_)
00206         {
00207                 win3D_ = CDisplayWindow3D::Create(
00208                         "pf-localization - The MRPT project", 1000, 600);
00209                 win3D_->setCameraZoom(20);
00210                 win3D_->setCameraAzimuthDeg(-45);
00211                 // win3D_->waitForKey();
00212 
00213                 // Create the 3D scene and get the map only once, later we'll modify
00214                 // only the particles, etc..
00215                 COccupancyGridMap2D::TEntropyInfo grid_info;
00216                 // The gridmap:
00217 #if MRPT_VERSION >= 0x199
00218                 if (metric_map_.countMapsByClass<COccupancyGridMap2D>())
00219                 {
00220                         metric_map_.mapByClass<COccupancyGridMap2D>()->computeEntropy(
00221                                 grid_info);
00222                 }
00223 #else
00224                 if (metric_map_.m_gridMaps.size())
00225                 {
00226                         metric_map_.m_gridMaps[0]->computeEntropy(grid_info);
00227                 }
00228 #endif
00229                 else
00230                 {
00231                         grid_info.effectiveMappedArea = (init_PDF_max_x - init_PDF_min_x) *
00232                                                                                         (init_PDF_max_y - init_PDF_min_y);
00233                 }
00234                 log_info(
00235                         "The gridmap has %.04fm2 observed area, %u observed cells\n",
00236                         grid_info.effectiveMappedArea,
00237                         (unsigned)grid_info.effectiveMappedCells);
00238                 log_info(
00239                         "Initial PDF: %f particles/m2\n",
00240                         initial_particle_count_ / grid_info.effectiveMappedArea);
00241 
00242                 auto plane = CSetOfObjects::Create();
00243                 metric_map_.getAs3DObject(plane);
00244                 scene_.insert(plane);
00245 
00246                 if (SHOW_PROGRESS_3D_REAL_TIME_)
00247                 {
00248                         COpenGLScene::Ptr ptr_scene = win3D_->get3DSceneAndLock();
00249 
00250                         ptr_scene->insert(plane);
00251 
00252                         ptr_scene->enableFollowCamera(true);
00253 
00254                         win3D_->unlockAccess3DScene();
00255                 }
00256         }  // Show 3D?
00257         if (param_->debug)
00258                 log_info(" --------------------------- init3DDebug done \n");
00259         if (param_->debug) fflush(stdout);
00260 }
00261 
00262 void PFLocalization::show3DDebug(CSensoryFrame::Ptr _observations)
00263 {
00264         // Create 3D window if requested:
00265         if (SHOW_PROGRESS_3D_REAL_TIME_)
00266         {
00267                 TTimeStamp cur_obs_timestamp = INVALID_TIMESTAMP;
00268                 if (_observations->size() > 0)
00269                         cur_obs_timestamp =
00270                                 _observations->getObservationByIndex(0)->timestamp;
00271 
00272 #if MRPT_VERSION >= 0x199
00273                 const auto [cov, meanPose] = pdf_.getCovarianceAndMean();
00274 #else
00275                 CPose2D meanPose;
00276                 CMatrixDouble33 cov;
00277                 pdf_.getCovarianceAndMean(cov, meanPose);
00278 #endif
00279 
00280                 COpenGLScene::Ptr ptr_scene = win3D_->get3DSceneAndLock();
00281 
00282                 win3D_->setCameraPointingToPoint(meanPose.x(), meanPose.y(), 0);
00283                 win3D_->addTextMessage(
00284                         10, 10,
00285                         mrpt::format(
00286                                 "timestamp: %s",
00287                                 cur_obs_timestamp != INVALID_TIMESTAMP
00288                                         ? mrpt::system::dateTimeLocalToString(cur_obs_timestamp)
00289                                                   .c_str()
00290                                         : "(none)"),
00291                         TColorf(.8f, .8f, .8f), "mono", 15, mrpt::opengl::NICE, 6001);
00292 
00293                 win3D_->addTextMessage(
00294                         10, 33,
00295                         mrpt::format(
00296                                 "#particles= %7u", static_cast<unsigned int>(pdf_.size())),
00297                         TColorf(.8f, .8f, .8f), "mono", 15, mrpt::opengl::NICE, 6002);
00298 
00299                 win3D_->addTextMessage(
00300                         10, 55,
00301                         mrpt::format(
00302                                 "mean pose (x y phi_deg)= %s", meanPose.asString().c_str()),
00303                         TColorf(.8f, .8f, .8f), "mono", 15, mrpt::opengl::NICE, 6003);
00304 
00305                 // The particles:
00306                 {
00307                         CRenderizable::Ptr parts = ptr_scene->getByName("particles");
00308                         if (parts) ptr_scene->removeObject(parts);
00309 
00310                         CSetOfObjects::Ptr p = pdf_.getAs3DObject<CSetOfObjects::Ptr>();
00311                         p->setName("particles");
00312                         ptr_scene->insert(p);
00313                 }
00314 
00315                 // The particles' cov:
00316                 {
00317                         CRenderizable::Ptr ellip = ptr_scene->getByName("parts_cov");
00318                         if (!ellip)
00319                         {
00320                                 auto o = CEllipsoid::Create();
00321                                 ellip = o;
00322                                 ellip->setName("parts_cov");
00323                                 ellip->setColor(1, 0, 0, 0.6);
00324 
00325                                 o->setLineWidth(2);
00326                                 o->setQuantiles(3);
00327                                 o->set2DsegmentsCount(60);
00328                                 ptr_scene->insert(ellip);
00329                         }
00330                         ellip->setLocation(meanPose.x(), meanPose.y(), 0.05);
00331 #if MRPT_VERSION >= 0x199
00332                         dynamic_cast<CEllipsoid*>(ellip.get())->setCovMatrix(cov, 2);
00333 #else
00334 
00335 #endif
00336                 }
00337 
00338                 // The laser scan:
00339                 {
00340                         CRenderizable::Ptr scan_pts = ptr_scene->getByName("scan");
00341                         if (!scan_pts)
00342                         {
00343                                 auto o = CPointCloud::Create();
00344                                 scan_pts = o;
00345                                 scan_pts->setName("scan");
00346                                 scan_pts->setColor(1, 0, 0, 0.9);
00347                                 o->enableColorFromZ(false);
00348                                 o->setPointSize(4);
00349                                 ptr_scene->insert(scan_pts);
00350                         }
00351 
00352                         CSimplePointsMap map;
00353                         static CSimplePointsMap last_map;
00354 
00355                         CPose3D robot_pose_3D(meanPose);
00356 
00357                         map.clear();
00358                         _observations->insertObservationsInto(&map);
00359 
00360                         dynamic_cast<CPointCloud*>(scan_pts.get())
00361                                 ->loadFromPointsMap(&last_map);
00362                         dynamic_cast<CPointCloud*>(scan_pts.get())->setPose(robot_pose_3D);
00363                         last_map = map;
00364                 }
00365 
00366                 // The camera:
00367                 ptr_scene->enableFollowCamera(true);
00368 
00369                 // Views:
00370                 COpenGLViewport::Ptr view1 = ptr_scene->getViewport("main");
00371                 {
00372                         CCamera& cam = view1->getCamera();
00373                         cam.setAzimuthDegrees(-90);
00374                         cam.setElevationDegrees(90);
00375                         cam.setPointingAt(meanPose);
00376                         cam.setZoomDistance(5);
00377                         cam.setOrthogonal();
00378                 }
00379 
00380                 win3D_->unlockAccess3DScene();
00381 
00382                 // Move camera:
00383                 // win3D_->setCameraPointingToPoint( curRobotPose.x, curRobotPose.y,
00384                 // curRobotPose.z );
00385 
00386                 // Update:
00387                 win3D_->forceRepaint();
00388 
00389                 std::this_thread::sleep_for(
00390                         std::chrono::milliseconds(SHOW_PROGRESS_3D_REAL_TIME_DELAY_MS_));
00391         }
00392 }


mrpt_localization
Author(s): Markus Bader, Raphael Zack
autogenerated on Thu Jun 6 2019 21:53:18