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 // JLB: I really can't explain this, but if this header is not included here
00038 // (though unneeded!)
00039 // the behavior of the particle filter does not converge as expected (WTF!!!)
00040 // (Verified with MRPT 1.0.2 & 1.3.0)
00041 #define MRPT_NO_WARN_BIG_HDR
00042 #include <mrpt/base.h>
00043 
00044 #include <mrpt_bridge/map.h>
00045 
00046 #include <mrpt/system/filesystem.h>
00047 #include <mrpt/opengl/CEllipsoid.h>
00048 #include <mrpt/opengl/CPointCloud.h>
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::utils;
00057 using namespace mrpt::bayes;
00058 using namespace mrpt::poses;
00059 using namespace std;
00060 
00061 #include <mrpt/version.h>
00062 using namespace mrpt::maps;
00063 using namespace mrpt::obs;
00064 
00065 PFLocalization::~PFLocalization() {}
00066 PFLocalization::PFLocalization(Parameters* param)
00067         : PFLocalizationCore(), param_(param)
00068 {
00069 }
00070 
00071 void PFLocalization::init()
00072 {
00073         log_info("ini_file ready %s", param_->ini_file.c_str());
00074         ASSERT_FILE_EXISTS_(param_->ini_file);
00075         log_info("ASSERT_FILE_EXISTS_ %s", param_->ini_file.c_str());
00076         mrpt::utils::CConfigFile ini_file;
00077         ini_file.setFileName(param_->ini_file);
00078         log_info("CConfigFile %s", param_->ini_file.c_str());
00079 
00080         vector_int particles_count;  // Number of initial particles (if size>1, run
00081         // the experiments N times)
00082 
00083         // Load configuration:
00084         // -----------------------------------------
00085         string iniSectionName("LocalizationExperiment");
00086         update_counter_ = 0;
00087 
00088         // Mandatory entries:
00089         ini_file.read_vector(
00090                 iniSectionName, "particles_count", vector_int(1, 0), particles_count,
00091                 /*Fail if not found*/ true);
00092 
00093         if (param_->map_file.empty())
00094         {
00095                 param_->map_file = ini_file.read_string(iniSectionName, "map_file", "");
00096         }
00097 
00098         // Non-mandatory entries:
00099         SCENE3D_FREQ_ = ini_file.read_int(iniSectionName, "3DSceneFrequency", 10);
00100         SCENE3D_FOLLOW_ =
00101                 ini_file.read_bool(iniSectionName, "3DSceneFollowRobot", true);
00102 
00103         SHOW_PROGRESS_3D_REAL_TIME_ =
00104                 ini_file.read_bool(iniSectionName, "SHOW_PROGRESS_3D_REAL_TIME", false);
00105         SHOW_PROGRESS_3D_REAL_TIME_DELAY_MS_ = ini_file.read_int(
00106                 iniSectionName, "SHOW_PROGRESS_3D_REAL_TIME_DELAY_MS", 1);
00107 
00108 #if !MRPT_HAS_WXWIDGETS
00109         SHOW_PROGRESS_3D_REAL_TIME_ = false;
00110 #endif
00111 
00112         // Default odometry uncertainty parameters in "odom_params_default_"
00113         // depending on how fast the robot moves, etc...
00114         //  Only used for observations-only rawlogs:
00115         motion_model_default_options_.modelSelection =
00116                 CActionRobotMovement2D::mmGaussian;
00117 
00118         motion_model_default_options_.gaussianModel.minStdXY =
00119                 ini_file.read_double("DummyOdometryParams", "minStdXY", 0.04);
00120         motion_model_default_options_.gaussianModel.minStdPHI = DEG2RAD(
00121                 ini_file.read_double("DefaultOdometryParams", "minStdPHI", 2.0));
00122 
00123         // Read initial particles distribution; fail if any parameter is not found
00124         init_PDF_mode =
00125                 ini_file.read_bool(iniSectionName, "init_PDF_mode", false, true);
00126         init_PDF_min_x =
00127                 ini_file.read_float(iniSectionName, "init_PDF_min_x", 0, true);
00128         init_PDF_max_x =
00129                 ini_file.read_float(iniSectionName, "init_PDF_max_x", 0, true);
00130         init_PDF_min_y =
00131                 ini_file.read_float(iniSectionName, "init_PDF_min_y", 0, true);
00132         init_PDF_max_y =
00133                 ini_file.read_float(iniSectionName, "init_PDF_max_y", 0, true);
00134         float min_phi = DEG2RAD(
00135                 ini_file.read_float(iniSectionName, "init_PDF_min_phi_deg", -180));
00136         float max_phi = DEG2RAD(
00137                 ini_file.read_float(iniSectionName, "init_PDF_max_phi_deg", 180));
00138         mrpt::poses::CPose2D p;
00139         mrpt::math::CMatrixDouble33 cov;
00140         cov(0, 0) = fabs(init_PDF_max_x - init_PDF_min_x);
00141         cov(1, 1) = fabs(init_PDF_max_y - init_PDF_min_y);
00142         cov(2, 2) =
00143                 min_phi < max_phi ? max_phi - min_phi : (max_phi + 2 * M_PI) - min_phi;
00144         p.x() = init_PDF_min_x + cov(0, 0) / 2.0;
00145         p.y() = init_PDF_min_y + cov(1, 1) / 2.0;
00146         p.phi() = min_phi + cov(2, 2) / 2.0;
00147         log_debug(
00148                 "----------- phi: %4.3f: %4.3f <-> %4.3f, %4.3f\n", p.phi(), min_phi,
00149                 max_phi, cov(2, 2));
00150         initial_pose_ = mrpt::poses::CPosePDFGaussian(p, cov);
00151         state_ = INIT;
00152 
00153         configureFilter(ini_file);
00154         // Metric map options:
00155 
00156         if (!mrpt_bridge::MapHdl::loadMap(
00157                         metric_map_, ini_file, param_->map_file, "metricMap",
00158                         param_->debug))
00159         {
00160                 waitForMap();
00161         }
00162 
00163         initial_particle_count_ = *particles_count.begin();
00164 
00165         if (param_->gui_mrpt) init3DDebug();
00166 }
00167 
00168 void PFLocalization::configureFilter(
00169         const mrpt::utils::CConfigFile& _configFile)
00170 {
00171         // PF-algorithm Options:
00172         // ---------------------------
00173         CParticleFilter::TParticleFilterOptions pfOptions;
00174         pfOptions.loadFromConfigFile(_configFile, "PF_options");
00175         pfOptions.dumpToConsole();
00176 
00177         // PDF Options:
00178         // ------------------
00179         TMonteCarloLocalizationParams pdfPredictionOptions;
00180         pdfPredictionOptions.KLD_params.loadFromConfigFile(
00181                 _configFile, "KLD_options");
00182 
00183         pdf_.clear();
00184 
00185         // PDF Options:
00186         pdf_.options = pdfPredictionOptions;
00187 
00188         pdf_.options.metricMap = &metric_map_;
00189 
00190         // Create the PF object:
00191         pf_.m_options = pfOptions;
00192 }
00193 
00194 void PFLocalization::init3DDebug()
00195 {
00196         log_info("init3DDebug");
00197         if (!SHOW_PROGRESS_3D_REAL_TIME_) return;
00198         if (!win3D_)
00199         {
00200                 win3D_ = CDisplayWindow3D::Create(
00201                         "pf-localization - The MRPT project", 1000, 600);
00202                 win3D_->setCameraZoom(20);
00203                 win3D_->setCameraAzimuthDeg(-45);
00204                 // win3D_->waitForKey();
00205 
00206                 // Create the 3D scene and get the map only once, later we'll modify
00207                 // only the particles, etc..
00208                 COccupancyGridMap2D::TEntropyInfo grid_info;
00209                 // The gridmap:
00210                 if (metric_map_.m_gridMaps.size())
00211                 {
00212                         metric_map_.m_gridMaps[0]->computeEntropy(grid_info);
00213                 }
00214                 else
00215                 {
00216                         grid_info.effectiveMappedArea = (init_PDF_max_x - init_PDF_min_x) *
00217                                                                                         (init_PDF_max_y - init_PDF_min_y);
00218                 }
00219                 log_info(
00220                         "The gridmap has %.04fm2 observed area, %u observed cells\n",
00221                         grid_info.effectiveMappedArea,
00222                         (unsigned)grid_info.effectiveMappedCells);
00223                 log_info(
00224                         "Initial PDF: %f particles/m2\n",
00225                         initial_particle_count_ / grid_info.effectiveMappedArea);
00226 
00227                 CSetOfObjects::Ptr plane = mrpt::make_aligned_shared<CSetOfObjects>();
00228                 metric_map_.getAs3DObject(plane);
00229                 scene_.insert(plane);
00230 
00231                 if (SHOW_PROGRESS_3D_REAL_TIME_)
00232                 {
00233                         COpenGLScene::Ptr ptr_scene = win3D_->get3DSceneAndLock();
00234 
00235                         ptr_scene->insert(plane);
00236 
00237                         ptr_scene->enableFollowCamera(true);
00238 
00239                         win3D_->unlockAccess3DScene();
00240                 }
00241         }  // Show 3D?
00242         if (param_->debug)
00243                 log_info(" --------------------------- init3DDebug done \n");
00244         if (param_->debug) fflush(stdout);
00245 }
00246 
00247 void PFLocalization::show3DDebug(CSensoryFrame::Ptr _observations)
00248 {
00249         // Create 3D window if requested:
00250         if (SHOW_PROGRESS_3D_REAL_TIME_)
00251         {
00252                 TTimeStamp cur_obs_timestamp;
00253                 if (_observations->size() > 0)
00254                         cur_obs_timestamp =
00255                                 _observations->getObservationByIndex(0)->timestamp;
00256 
00257                 CPose2D meanPose;
00258                 CMatrixDouble33 cov;
00259                 pdf_.getCovarianceAndMean(cov, meanPose);
00260 
00261                 COpenGLScene::Ptr ptr_scene = win3D_->get3DSceneAndLock();
00262 
00263                 win3D_->setCameraPointingToPoint(meanPose.x(), meanPose.y(), 0);
00264                 win3D_->addTextMessage(
00265                         10, 10,
00266                         mrpt::format(
00267                                 "timestamp: %s",
00268                                 mrpt::system::dateTimeLocalToString(cur_obs_timestamp).c_str()),
00269                         mrpt::utils::TColorf(.8f, .8f, .8f), "mono", 15, mrpt::opengl::NICE,
00270                         6001);
00271 
00272                 win3D_->addTextMessage(
00273                         10, 33,
00274                         mrpt::format(
00275                                 "#particles= %7u", static_cast<unsigned int>(pdf_.size())),
00276                         mrpt::utils::TColorf(.8f, .8f, .8f), "mono", 15, mrpt::opengl::NICE,
00277                         6002);
00278 
00279                 win3D_->addTextMessage(
00280                         10, 55,
00281                         mrpt::format(
00282                                 "mean pose (x y phi_deg)= %s", meanPose.asString().c_str()),
00283                         mrpt::utils::TColorf(.8f, .8f, .8f), "mono", 15, mrpt::opengl::NICE,
00284                         6003);
00285 
00286                 // The particles:
00287                 {
00288                         CRenderizable::Ptr parts = ptr_scene->getByName("particles");
00289                         if (parts) ptr_scene->removeObject(parts);
00290 
00291                         CSetOfObjects::Ptr p = pdf_.getAs3DObject<CSetOfObjects::Ptr>();
00292                         p->setName("particles");
00293                         ptr_scene->insert(p);
00294                 }
00295 
00296                 // The particles' cov:
00297                 {
00298                         CRenderizable::Ptr ellip = ptr_scene->getByName("parts_cov");
00299                         if (!ellip)
00300                         {
00301                                 ellip = mrpt::make_aligned_shared<CEllipsoid>();
00302                                 ellip->setName("parts_cov");
00303                                 ellip->setColor(1, 0, 0, 0.6);
00304 
00305                                 getAs<CEllipsoid>(ellip)->setLineWidth(2);
00306                                 getAs<CEllipsoid>(ellip)->setQuantiles(3);
00307                                 getAs<CEllipsoid>(ellip)->set2DsegmentsCount(60);
00308                                 ptr_scene->insert(ellip);
00309                         }
00310                         ellip->setLocation(meanPose.x(), meanPose.y(), 0.05);
00311 
00312                         getAs<CEllipsoid>(ellip)->setCovMatrix(cov, 2);
00313                 }
00314 
00315                 // The laser scan:
00316                 {
00317                         CRenderizable::Ptr scan_pts = ptr_scene->getByName("scan");
00318                         if (!scan_pts)
00319                         {
00320                                 scan_pts = mrpt::make_aligned_shared<CPointCloud>();
00321                                 scan_pts->setName("scan");
00322                                 scan_pts->setColor(1, 0, 0, 0.9);
00323                                 getAs<CPointCloud>(scan_pts)->enableColorFromZ(false);
00324                                 getAs<CPointCloud>(scan_pts)->setPointSize(4);
00325                                 ptr_scene->insert(scan_pts);
00326                         }
00327 
00328                         CSimplePointsMap map;
00329                         static CSimplePointsMap last_map;
00330 
00331                         CPose3D robot_pose_3D(meanPose);
00332 
00333                         map.clear();
00334                         _observations->insertObservationsInto(&map);
00335 
00336                         getAs<CPointCloud>(scan_pts)->loadFromPointsMap(&last_map);
00337                         getAs<CPointCloud>(scan_pts)->setPose(robot_pose_3D);
00338                         last_map = map;
00339                 }
00340 
00341                 // The camera:
00342                 ptr_scene->enableFollowCamera(true);
00343 
00344                 // Views:
00345                 COpenGLViewport::Ptr view1 = ptr_scene->getViewport("main");
00346                 {
00347                         CCamera& cam = view1->getCamera();
00348                         cam.setAzimuthDegrees(-90);
00349                         cam.setElevationDegrees(90);
00350                         cam.setPointingAt(meanPose);
00351                         cam.setZoomDistance(5);
00352                         cam.setOrthogonal();
00353                 }
00354 
00355                 win3D_->unlockAccess3DScene();
00356 
00357                 // Move camera:
00358                 // win3D_->setCameraPointingToPoint( curRobotPose.x, curRobotPose.y,
00359                 // curRobotPose.z );
00360 
00361                 // Update:
00362                 win3D_->forceRepaint();
00363 
00364                 sleep(SHOW_PROGRESS_3D_REAL_TIME_DELAY_MS_);
00365         }
00366 }


mrpt_localization
Author(s): Markus Bader, Raphael Zack
autogenerated on Mon Sep 18 2017 03:12:10