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" AND *
00018  * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED   *
00019  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE          *
00020  * DISCLAIMED. IN NO EVENT SHALL Markus Bader BE LIABLE FOR ANY                    *
00021  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES      *
00022  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;    *
00023  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND     *
00024  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT      *
00025  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS   *
00026  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.                    *                       *
00027  ***********************************************************************************/
00028 
00029 
00030 #include <mrpt_localization/mrpt_localization.h>
00031 #include <mrpt_localization/mrpt_localization_defaults.h>
00032 
00033 #include <mrpt/base.h>
00034 #include <mrpt/slam.h>
00035 #include <mrpt_bridge/map.h>
00036 
00037 using namespace mrpt;
00038 using namespace mrpt::slam;
00039 using namespace mrpt::opengl;
00040 using namespace mrpt::gui;
00041 using namespace mrpt::math;
00042 using namespace mrpt::system;
00043 using namespace mrpt::utils;
00044 using namespace mrpt::random;
00045 using namespace std;
00046 
00047 
00048 PFLocalization::~PFLocalization()
00049 {
00050 }
00051 
00052 PFLocalization::PFLocalization(Parameters *param)
00053     : PFLocalizationCore(), param_(param) {
00054 }
00055 
00056 void PFLocalization::init() {
00057     printf("iniFile ready %s\n", param_->iniFile.c_str());
00058     ASSERT_FILE_EXISTS_(param_->iniFile);
00059     printf("ASSERT_FILE_EXISTS_ %s\n", param_->iniFile.c_str());
00060     mrpt::utils::CConfigFile iniFile;
00061     iniFile.setFileName(param_->iniFile);
00062     printf("CConfigFile %s\n", param_->iniFile.c_str());
00063 
00064 
00065     vector_int          particles_count;    // Number of initial particles (if size>1, run the experiments N times)
00066 
00067     // Load configuration:
00068     // -----------------------------------------
00069     string iniSectionName ( "LocalizationExperiment" );
00070     update_counter_ = 0;
00071 
00072     // Mandatory entries:
00073     iniFile.read_vector(iniSectionName, "particles_count", vector_int(1,0), particles_count, /*Fail if not found*/true );
00074 
00075 
00076     if (param_->mapFile.empty()) {
00077         param_->mapFile = iniFile.read_string(iniSectionName,"map_file","" );
00078     }
00079 
00080     // Non-mandatory entries:
00081     SCENE3D_FREQ_        = iniFile.read_int(iniSectionName,"3DSceneFrequency",10);
00082     SCENE3D_FOLLOW_      = iniFile.read_bool(iniSectionName,"3DSceneFollowRobot",true);
00083 
00084     SHOW_PROGRESS_3D_REAL_TIME_ = iniFile.read_bool(iniSectionName,"SHOW_PROGRESS_3D_REAL_TIME",false);
00085     SHOW_PROGRESS_3D_REAL_TIME_DELAY_MS_ = iniFile.read_int(iniSectionName,"SHOW_PROGRESS_3D_REAL_TIME_DELAY_MS",1);
00086 
00087 #if !MRPT_HAS_WXWIDGETS
00088     SHOW_PROGRESS_3D_REAL_TIME = false;
00089 #endif
00090 
00091     // Default odometry uncertainty parameters in "dummy_odom_params" depending on how fast the robot moves, etc...
00092     //  Only used for observations-only rawlogs:
00093 
00094     odom_params_dummy_.modelSelection = CActionRobotMovement2D::mmGaussian;
00095     odom_params_dummy_.gausianModel.minStdXY  = iniFile.read_double("DummyOdometryParams","minStdXY",0.04);
00096     odom_params_dummy_.gausianModel.minStdPHI = DEG2RAD(iniFile.read_double("DummyOdometryParams","minStdPHI", 2.0));
00097 
00098 
00099     if ( !iniFile.read_bool(iniSectionName,"init_PDF_mode",false, /*Fail if not found*/true) ) {
00100         float min_x = iniFile.read_float(iniSectionName,"init_PDF_min_x",0,true);
00101         float max_x = iniFile.read_float(iniSectionName,"init_PDF_max_x",0,true);
00102         float min_y = iniFile.read_float(iniSectionName,"init_PDF_min_y",0,true);
00103         float max_y = iniFile.read_float(iniSectionName,"init_PDF_max_y",0,true);
00104         float min_phi = DEG2RAD(iniFile.read_float(iniSectionName,"init_PDF_min_phi_deg",-180));
00105         float max_phi = DEG2RAD(iniFile.read_float(iniSectionName,"init_PDF_max_phi_deg",180));
00106         mrpt::poses::CPose2D p;
00107         mrpt::math::CMatrixDouble33 cov;
00108         cov(0,0) = fabs(max_x - min_x);
00109         cov(1,1) = fabs(max_x - min_x);
00110         cov(2,2) = min_phi<max_phi ? max_phi-min_phi : (max_phi+2*M_PI)-min_phi;
00111         p.x() = min_x + cov(0,0) / 2.0;
00112         p.y() = min_y + cov(1,1) / 2.0;
00113         p.phi() = min_phi + cov(2,2) / 2.0;
00114         printf("----------- phi: %4.3f: %4.3f <-> %4.3f, %4.3f\n", p.phi(), min_phi, max_phi, cov(2,2));
00115         initialPose_ = mrpt::utils::CPosePDFGaussian(p, cov);
00116     }
00117 
00118 
00119     configureFilter(iniFile);
00120     // Metric map options:
00121 
00122     if(!mrpt_bridge::MapHdl::loadMap(metric_map_, iniFile, param_->mapFile, "metricMap", param_->debug)) {
00123         waitForMap();
00124     }
00125 
00126     initialParticleCount_ = *particles_count.begin();
00127 
00128     if(param_->gui_mrpt) init3DDebug();
00129     initializeFilter(initialPose_);
00130 
00131 }
00132 
00133 void PFLocalization::configureFilter(const mrpt::utils::CConfigFile &_configFile) {
00134 
00135     // PF-algorithm Options:
00136     // ---------------------------
00137     CParticleFilter::TParticleFilterOptions     pfOptions;
00138     pfOptions.loadFromConfigFile( _configFile, "PF_options" );
00139     pfOptions.dumpToConsole();
00140 
00141     // PDF Options:
00142     // ------------------
00143     TMonteCarloLocalizationParams   pdfPredictionOptions;
00144     pdfPredictionOptions.KLD_params.loadFromConfigFile( _configFile, "KLD_options");
00145 
00146     pdf_.clear();
00147 
00148     // PDF Options:
00149     pdf_.options = pdfPredictionOptions;
00150 
00151     pdf_.options.metricMap = &metric_map_;
00152 
00153     // Create the PF object:
00154     pf_.m_options = pfOptions;
00155 }
00156 
00157 void PFLocalization::init3DDebug() {
00158     log_info("init3DDebug");   
00159     if (!SHOW_PROGRESS_3D_REAL_TIME_) return;
00160     if(!win3D_) {
00161         win3D_ = CDisplayWindow3D::Create("pf-localization - The MRPT project", 1000, 600);
00162         win3D_->setCameraZoom(20);
00163         win3D_->setCameraAzimuthDeg(-45);
00164         //win3D_->waitForKey();
00165 
00166         // Create the 3D scene and get the map only once, later we'll modify only the particles, etc..
00167         mrpt::slam::COccupancyGridMap2D::TEntropyInfo gridInfo;
00168         // The gridmap:
00169         if (metric_map_.m_gridMaps.size())
00170         {
00171             metric_map_.m_gridMaps[0]->computeEntropy( gridInfo );
00172             printf("The gridmap has %.04fm2 observed area, %u observed cells\n", gridInfo.effectiveMappedArea, (unsigned) gridInfo.effectiveMappedCells );
00173 
00174             {
00175                 CSetOfObjectsPtr plane = CSetOfObjects::Create();
00176                 metric_map_.m_gridMaps[0]->getAs3DObject( plane );
00177                 scene_.insert( plane );
00178             }
00179 
00180             if (SHOW_PROGRESS_3D_REAL_TIME_)
00181             {
00182                 COpenGLScenePtr ptrScene = win3D_->get3DSceneAndLock();
00183 
00184                 CSetOfObjectsPtr plane = CSetOfObjects::Create();
00185                 metric_map_.m_gridMaps[0]->getAs3DObject( plane );
00186                 ptrScene->insert( plane );
00187 
00188                 ptrScene->enableFollowCamera(true);
00189 
00190                 win3D_->unlockAccess3DScene();
00191             }
00192         }
00193         printf("Initial PDF: %f particles/m2\n", initialParticleCount_/gridInfo.effectiveMappedArea);
00194     } // Show 3D?
00195     if(param_->debug) printf(" --------------------------- init3DDebug done \n");
00196     if(param_->debug) fflush(stdout);
00197 }
00198 
00199 void PFLocalization::show3DDebug(CSensoryFramePtr _observations) {
00200     // Create 3D window if requested:
00201     if (SHOW_PROGRESS_3D_REAL_TIME_)
00202     {
00203         TTimeStamp cur_obs_timestamp;
00204         if (_observations->size()>0)
00205             cur_obs_timestamp = _observations->getObservationByIndex(0)->timestamp;
00206 
00207         CPose2D       meanPose;
00208         CMatrixDouble33 cov;
00209         pdf_.getCovarianceAndMean(cov,meanPose);
00210 
00211         COpenGLScenePtr ptrScene = win3D_->get3DSceneAndLock();
00212 
00213         win3D_->setCameraPointingToPoint(meanPose.x(),meanPose.y(),0);
00214         win3D_->addTextMessage(
00215             10,10, mrpt::format("timestamp: %s", mrpt::system::dateTimeLocalToString(cur_obs_timestamp).c_str() ),
00216             mrpt::utils::TColorf(.8f,.8f,.8f),
00217             "mono", 15, mrpt::opengl::NICE, 6001 );
00218 
00219         win3D_->addTextMessage(
00220             10,33, mrpt::format("#particles= %7u", static_cast<unsigned int>(pdf_.size()) ),
00221             mrpt::utils::TColorf(.8f,.8f,.8f),
00222             "mono", 15, mrpt::opengl::NICE, 6002 );
00223 
00224         win3D_->addTextMessage(
00225             10,55, mrpt::format("mean pose (x y phi_deg)= %s", meanPose.asString().c_str() ),
00226             mrpt::utils::TColorf(.8f,.8f,.8f),
00227             "mono", 15, mrpt::opengl::NICE, 6003 );
00228 
00229         // The particles:
00230         {
00231             CRenderizablePtr parts = ptrScene->getByName("particles");
00232             if (parts) ptrScene->removeObject(parts);
00233 
00234             CSetOfObjectsPtr p = pdf_.getAs3DObject<CSetOfObjectsPtr>();
00235             p->setName("particles");
00236             ptrScene->insert(p);
00237         }
00238 
00239         // The particles' cov:
00240         {
00241             CRenderizablePtr    ellip = ptrScene->getByName("parts_cov");
00242             if (!ellip)
00243             {
00244                 ellip = CEllipsoid::Create();
00245                 ellip->setName( "parts_cov");
00246                 ellip->setColor(1,0,0, 0.6);
00247 
00248                 getAs<CEllipsoid>(ellip)->setLineWidth(2);
00249                 getAs<CEllipsoid>(ellip)->setQuantiles(3);
00250                 getAs<CEllipsoid>(ellip)->set2DsegmentsCount(60);
00251                 ptrScene->insert( ellip );
00252             }
00253             ellip->setLocation(meanPose.x(), meanPose.y(), 0.05 );
00254 
00255             getAs<CEllipsoid>(ellip)->setCovMatrix(cov,2);
00256         }
00257 
00258 
00259         // The laser scan:
00260         {
00261             CRenderizablePtr scanPts = ptrScene->getByName("scan");
00262             if (!scanPts)
00263             {
00264                 scanPts = CPointCloud::Create();
00265                 scanPts->setName( "scan" );
00266                 scanPts->setColor(1,0,0, 0.9);
00267                 getAs<CPointCloud>(scanPts)->enableColorFromZ(false);
00268                 getAs<CPointCloud>(scanPts)->setPointSize(4);
00269                 ptrScene->insert(scanPts);
00270             }
00271 
00272             CSimplePointsMap    map;
00273             static CSimplePointsMap last_map;
00274 
00275             CPose3D             robotPose3D( meanPose );
00276 
00277             map.clear();
00278             _observations->insertObservationsInto( &map );
00279 
00280             getAs<CPointCloud>(scanPts)->loadFromPointsMap( &last_map );
00281             getAs<CPointCloud>(scanPts)->setPose( robotPose3D );
00282             last_map = map;
00283         }
00284 
00285         // The camera:
00286         ptrScene->enableFollowCamera(true);
00287 
00288         // Views:
00289         COpenGLViewportPtr view1= ptrScene->getViewport("main");
00290         {
00291             CCamera  &cam = view1->getCamera();
00292             cam.setAzimuthDegrees(-90);
00293             cam.setElevationDegrees(90);
00294             cam.setPointingAt( meanPose );
00295             cam.setZoomDistance(5);
00296             cam.setOrthogonal();
00297         }
00298 
00299         win3D_->unlockAccess3DScene();
00300 
00301         // Move camera:
00302         //win3D_->setCameraPointingToPoint( curRobotPose.x, curRobotPose.y, curRobotPose.z );
00303 
00304         // Update:
00305         win3D_->forceRepaint();
00306 
00307         sleep( SHOW_PROGRESS_3D_REAL_TIME_DELAY_MS_ );
00308     }
00309 }
00310 


mrpt_localization
Author(s):
autogenerated on Tue Aug 5 2014 10:58:12