mrpt_localization_core.cpp
Go to the documentation of this file.
1 /***********************************************************************************
2  * Revised BSD License *
3  * Copyright (c) 2014, Markus Bader <markus.bader@tuwien.ac.at> *
4  * All rights reserved. *
5  * *
6  * Redistribution and use in source and binary forms, with or without *
7  * modification, are permitted provided that the following conditions are met: *
8  * * Redistributions of source code must retain the above copyright *
9  * notice, this list of conditions and the following disclaimer. *
10  * * Redistributions in binary form must reproduce the above copyright *
11  * notice, this list of conditions and the following disclaimer in the *
12  * documentation and/or other materials provided with the distribution. *
13  * * Neither the name of the Vienna University of Technology nor the *
14  * names of its contributors may be used to endorse or promote products *
15  * derived from this software without specific prior written permission. *
16  * *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  *AND *
19  * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
20  **
21  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE *
22  * DISCLAIMED. IN NO EVENT SHALL Markus Bader BE LIABLE FOR ANY *
23  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES *
24  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
25  **
26  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND *
27  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT *
28  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
29  **
30  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
31  ** *
32  ***********************************************************************************/
33 
35 #include <mrpt/version.h>
36 
37 #include <mrpt/maps/COccupancyGridMap2D.h>
39 
40 #include <mrpt/maps/CLandmarksMap.h>
42 
43 using namespace mrpt;
44 using namespace mrpt::slam;
45 using namespace mrpt::opengl;
46 using namespace mrpt::math;
47 using namespace mrpt::system;
48 using namespace mrpt::utils;
49 using namespace std;
50 
54 {
56  cov(0, 0) = 1, cov(1, 1) = 1, cov(2, 2) = 2 * M_PI;
60 
62  CActionRobotMovement2D::mmGaussian;
65 }
66 
68 {
69 #if MRPT_VERSION >= 0x199
70  const auto [cov, mean_point] = initial_pose_.getCovarianceAndMean();
71 #else
73  mrpt::poses::CPose2D mean_point;
74  initial_pose_.getCovarianceAndMean(cov, mean_point);
75 #endif
76 
77  log_info(
78  "InitializeFilter: %4.3fm, %4.3fm, %4.3frad ", mean_point.x(),
79  mean_point.y(), mean_point.phi());
80  float min_x = mean_point.x() - cov(0, 0);
81  float max_x = mean_point.x() + cov(0, 0);
82  float min_y = mean_point.y() - cov(1, 1);
83  float max_y = mean_point.y() + cov(1, 1);
84  float min_phi = mean_point.phi() - cov(2, 2);
85  float max_phi = mean_point.phi() + cov(2, 2);
86 
87 #if MRPT_VERSION >= 0x199
88  if (metric_map_.countMapsByClass<COccupancyGridMap2D>() && !init_PDF_mode)
89  {
91  metric_map_.mapByClass<COccupancyGridMap2D>().get(), 0.7f,
92  initial_particle_count_, min_x, max_x, min_y, max_y, min_phi,
93  max_phi);
94  }
95  else if (metric_map_.countMapsByClass<CLandmarksMap>() || init_PDF_mode)
96 #else
98  {
101  min_x, max_x, min_y, max_y, min_phi, max_phi);
102  }
104 #endif
105  {
107  min_x, max_x, min_y, max_y, min_phi, max_phi,
109  }
110  state_ = RUN;
111 }
112 
114  CActionCollection::Ptr _action, CSensoryFrame::Ptr _sf)
115 {
116  if (state_ == INIT) initializeFilter();
117  tictac_.Tic();
118  pf_.executeOn(pdf_, _action.get(), _sf.get(), &pf_stats_);
119  time_last_update_ = _sf->getObservationByIndex(0)->timestamp;
120  update_counter_++;
121 }
122 
124  CSensoryFrame::Ptr _sf, CObservationOdometry::Ptr _odometry)
125 {
126  auto action = CActionCollection::Create();
127  CActionRobotMovement2D odom_move;
128  odom_move.timestamp = _sf->getObservationByIndex(0)->timestamp;
129  if (_odometry)
130  {
132  {
133  odom_last_observation_ = _odometry->odometry;
134  }
135  mrpt::poses::CPose2D incOdoPose =
136  _odometry->odometry - odom_last_observation_;
137  odom_last_observation_ = _odometry->odometry;
138  odom_move.computeFromOdometry(incOdoPose, motion_model_options_);
139  action->insert(odom_move);
140  updateFilter(action, _sf);
141  }
142  else
143  {
145  {
146  log_info(
147  "No odometry at update %4i -> using dummy", update_counter_);
148  odom_move.computeFromOdometry(
150  action->insert(odom_move);
151  updateFilter(action, _sf);
152  }
153  else
154  {
155  log_info(
156  "No odometry at update %4i -> skipping observation",
158  }
159  }
160 }
void resetUniformFreeSpace(mrpt::maps::COccupancyGridMap2D *theMap, const double freeCellsThreshold=0.7, const int particlesCount=-1, const double x_min=-1e10f, const double x_max=1e10f, const double y_min=-1e10f, const double y_max=1e10f, const double phi_min=-M_PI, const double phi_max=M_PI)
CMultiMetricMap metric_map_
map
void getCovarianceAndMean(mrpt::math::CMatrixDouble33 &out_cov, CPose2D &mean_point) const MRPT_OVERRIDE
void updateFilter(CActionCollection::Ptr _action, CSensoryFrame::Ptr _sf)
mrpt::utils::CTicTac tictac_
timer to measure performance
void executeOn(CParticleFilterCapable &obj, const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, TParticleFilterStats *stats=NULL)
mrpt::bayes::CParticleFilter::TParticleFilterStats pf_stats_
filter statistics
int initial_particle_count_
number of particles for initialization
#define M_PI
mrpt::poses::CPose2D odom_last_observation_
correct time
struct OBS_IMPEXP mrpt::obs::CActionRobotMovement2D::TMotionModelOptions::TOptions_GaussianModel gaussianModel
void observation(CSensoryFrame::Ptr _sf, CObservationOdometry::Ptr _odometry)
cov
const double & phi() const
mrpt::slam::CMonteCarloLocalization2D pdf_
the filter
mrpt::poses::CPosePDFGaussian initial_pose_
initial posed used in initializeFilter()
ProxySelectorContainerByClass< mrpt::maps::CLandmarksMapPtr, TListMaps > m_landmarksMap
static bool empty()
CActionRobotMovement2D::TMotionModelOptions motion_model_options_
used with odom value motion noise
action
ProxyFilterContainerByClass< mrpt::maps::COccupancyGridMap2DPtr, TListMaps > m_gridMaps
mrpt::bayes::CParticleFilter pf_
common interface for particle filters
mrpt::system::TTimeStamp time_last_update_
time of the last update
bool use_motion_model_default_options_
used default odom_params
CActionRobotMovement2D::TMotionModelOptions motion_model_default_options_
used if there are is not odom
void computeFromOdometry(const mrpt::poses::CPose2D &odometryIncrement, const TMotionModelOptions &options)
void resetUniform(const double &x_min, const double &x_max, const double &y_min, const double &y_max, const double &phi_min=-M_PI, const double &phi_max=M_PI, const int &particlesCount=-1)


mrpt_localization
Author(s): Markus Bader, Raphael Zack
autogenerated on Thu Mar 12 2020 03:21:48