00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
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 }