mrpt_localization_core.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_core.h>
00035 #include <mrpt/version.h>
00036 
00037 #include <mrpt/maps/COccupancyGridMap2D.h>
00038 using mrpt::maps::COccupancyGridMap2D;
00039 
00040 #include <mrpt/maps/CLandmarksMap.h>
00041 using mrpt::maps::CLandmarksMap;
00042 
00043 using namespace mrpt;
00044 using namespace mrpt::slam;
00045 using namespace mrpt::opengl;
00046 using namespace mrpt::math;
00047 using namespace mrpt::system;
00048 using namespace mrpt::utils;
00049 using namespace std;
00050 
00051 PFLocalizationCore::~PFLocalizationCore() {}
00052 PFLocalizationCore::PFLocalizationCore() : state_(NA) {}
00053 void PFLocalizationCore::init()
00054 {
00055         mrpt::math::CMatrixDouble33 cov;
00056         cov(0, 0) = 1, cov(1, 1) = 1, cov(2, 2) = 2 * M_PI;
00057         initial_pose_ =
00058                 mrpt::poses::CPosePDFGaussian(mrpt::poses::CPose2D(0, 0, 0), cov);
00059         initial_particle_count_ = 1000;
00060 
00061         motion_model_default_options_.modelSelection =
00062                 CActionRobotMovement2D::mmGaussian;
00063         motion_model_default_options_.gaussianModel.minStdXY = 0.10;
00064         motion_model_default_options_.gaussianModel.minStdPHI = 2.0;
00065 }
00066 
00067 void PFLocalizationCore::initializeFilter()
00068 {
00069 #if MRPT_VERSION >= 0x199
00070         const auto [cov, mean_point] = initial_pose_.getCovarianceAndMean();
00071 #else
00072         mrpt::math::CMatrixDouble33 cov;
00073         mrpt::poses::CPose2D mean_point;
00074         initial_pose_.getCovarianceAndMean(cov, mean_point);
00075 #endif
00076 
00077         log_info(
00078                 "InitializeFilter: %4.3fm, %4.3fm, %4.3frad ", mean_point.x(),
00079                 mean_point.y(), mean_point.phi());
00080         float min_x = mean_point.x() - cov(0, 0);
00081         float max_x = mean_point.x() + cov(0, 0);
00082         float min_y = mean_point.y() - cov(1, 1);
00083         float max_y = mean_point.y() + cov(1, 1);
00084         float min_phi = mean_point.phi() - cov(2, 2);
00085         float max_phi = mean_point.phi() + cov(2, 2);
00086 
00087 #if MRPT_VERSION >= 0x199
00088         if (metric_map_.countMapsByClass<COccupancyGridMap2D>() && !init_PDF_mode)
00089         {
00090                 pdf_.resetUniformFreeSpace(
00091                         metric_map_.mapByClass<COccupancyGridMap2D>().get(), 0.7f,
00092                         initial_particle_count_, min_x, max_x, min_y, max_y, min_phi,
00093                         max_phi);
00094         }
00095         else if (metric_map_.countMapsByClass<CLandmarksMap>() || init_PDF_mode)
00096 #else
00097         if (metric_map_.m_gridMaps.size() && !init_PDF_mode)
00098         {
00099                 pdf_.resetUniformFreeSpace(
00100                         metric_map_.m_gridMaps[0].get(), 0.7f, initial_particle_count_,
00101                         min_x, max_x, min_y, max_y, min_phi, max_phi);
00102         }
00103         else if (metric_map_.m_landmarksMap || init_PDF_mode)
00104 #endif
00105         {
00106                 pdf_.resetUniform(
00107                         min_x, max_x, min_y, max_y, min_phi, max_phi,
00108                         initial_particle_count_);
00109         }
00110         state_ = RUN;
00111 }
00112 
00113 void PFLocalizationCore::updateFilter(
00114         CActionCollection::Ptr _action, CSensoryFrame::Ptr _sf)
00115 {
00116         if (state_ == INIT) initializeFilter();
00117         tictac_.Tic();
00118         pf_.executeOn(pdf_, _action.get(), _sf.get(), &pf_stats_);
00119         time_last_update_ = _sf->getObservationByIndex(0)->timestamp;
00120         update_counter_++;
00121 }
00122 
00123 void PFLocalizationCore::observation(
00124         CSensoryFrame::Ptr _sf, CObservationOdometry::Ptr _odometry)
00125 {
00126         auto action = CActionCollection::Create();
00127         CActionRobotMovement2D odom_move;
00128         odom_move.timestamp = _sf->getObservationByIndex(0)->timestamp;
00129         if (_odometry)
00130         {
00131                 if (odom_last_observation_.empty())
00132                 {
00133                         odom_last_observation_ = _odometry->odometry;
00134                 }
00135                 mrpt::poses::CPose2D incOdoPose =
00136                         _odometry->odometry - odom_last_observation_;
00137                 odom_last_observation_ = _odometry->odometry;
00138                 odom_move.computeFromOdometry(incOdoPose, motion_model_options_);
00139                 action->insert(odom_move);
00140                 updateFilter(action, _sf);
00141         }
00142         else
00143         {
00144                 if (use_motion_model_default_options_)
00145                 {
00146                         log_info(
00147                                 "No odometry at update %4i -> using dummy", update_counter_);
00148                         odom_move.computeFromOdometry(
00149                                 mrpt::poses::CPose2D(0, 0, 0), motion_model_default_options_);
00150                         action->insert(odom_move);
00151                         updateFilter(action, _sf);
00152                 }
00153                 else
00154                 {
00155                         log_info(
00156                                 "No odometry at update %4i -> skipping observation",
00157                                 update_counter_);
00158                 }
00159         }
00160 }


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