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