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 
34 #include <mrpt/maps/CLandmarksMap.h>
35 #include <mrpt/maps/COccupancyGridMap2D.h>
37 #include <ros/console.h>
38 
39 using namespace mrpt;
40 using namespace mrpt::slam;
41 using namespace mrpt::opengl;
42 using namespace mrpt::math;
43 using namespace mrpt::system;
44 using namespace std;
45 
46 using mrpt::maps::CLandmarksMap;
47 using mrpt::maps::COccupancyGridMap2D;
48 
52 {
53  mrpt::math::CMatrixDouble33 cov;
54  cov(0, 0) = 1, cov(1, 1) = 1, cov(2, 2) = 2 * M_PI;
56  mrpt::poses::CPosePDFGaussian(mrpt::poses::CPose2D(0, 0, 0), cov);
58 
59  motion_model_default_options_.modelSelection =
60  CActionRobotMovement2D::mmGaussian;
61  motion_model_default_options_.gaussianModel.minStdXY = 0.10;
62  motion_model_default_options_.gaussianModel.minStdPHI = 2.0;
63 }
64 
66 {
67  const auto [cov, mean_point] = initial_pose_.getCovarianceAndMean();
68 
69  ROS_INFO(
70  "InitializeFilter: %4.3fm, %4.3fm, %4.3frad ", mean_point.x(),
71  mean_point.y(), mean_point.phi());
72  float min_x = mean_point.x() - cov(0, 0);
73  float max_x = mean_point.x() + cov(0, 0);
74  float min_y = mean_point.y() - cov(1, 1);
75  float max_y = mean_point.y() + cov(1, 1);
76  float min_phi = mean_point.phi() - cov(2, 2);
77  float max_phi = mean_point.phi() + cov(2, 2);
78 
79  if (metric_map_->countMapsByClass<COccupancyGridMap2D>() && !init_PDF_mode)
80  {
81  pdf_.resetUniformFreeSpace(
82  metric_map_->mapByClass<COccupancyGridMap2D>().get(), 0.7f,
83  initial_particle_count_, min_x, max_x, min_y, max_y, min_phi,
84  max_phi);
85  }
86  else if (metric_map_->countMapsByClass<CLandmarksMap>() || init_PDF_mode)
87  {
88  pdf_.resetUniform(
89  min_x, max_x, min_y, max_y, min_phi, max_phi,
91  }
92  state_ = RUN;
93 }
94 
96  CActionCollection::Ptr _action, CSensoryFrame::Ptr _sf)
97 {
98  if (state_ == INIT) initializeFilter();
99  tictac_.Tic();
100  pf_.executeOn(pdf_, _action.get(), _sf.get(), &pf_stats_);
101  time_last_update_ = _sf->getObservationByIndex(0)->timestamp;
102  update_counter_++;
103 }
104 
106  CSensoryFrame::Ptr _sf, CObservationOdometry::Ptr _odometry)
107 {
108  auto action = CActionCollection::Create();
109  CActionRobotMovement2D odom_move;
110  odom_move.timestamp = _sf->getObservationByIndex(0)->timestamp;
111  if (_odometry)
112  {
113  if (odom_last_observation_.empty())
114  {
115  odom_last_observation_ = _odometry->odometry;
116  }
117  mrpt::poses::CPose2D incOdoPose =
118  _odometry->odometry - odom_last_observation_;
119  odom_last_observation_ = _odometry->odometry;
120  odom_move.computeFromOdometry(incOdoPose, motion_model_options_);
121  action->insert(odom_move);
122  updateFilter(action, _sf);
123  }
124  else
125  {
127  {
129  "No odometry at update " << update_counter_
130  << " -> using dummy");
131  odom_move.computeFromOdometry(
132  mrpt::poses::CPose2D(0, 0, 0), motion_model_default_options_);
133  action->insert(odom_move);
134  updateFilter(action, _sf);
135  }
136  else
137  {
139  "No odometry at update " << update_counter_
140  << " -> skipping observation");
141  }
142  }
143 }
PFLocalizationCore::initializeFilter
void initializeFilter()
Definition: mrpt_localization_core.cpp:65
PFLocalizationCore::pf_
mrpt::bayes::CParticleFilter pf_
common interface for particle filters
Definition: mrpt_localization_core.h:90
mrpt_localization_core.h
PFLocalizationCore::time_last_update_
mrpt::system::TTimeStamp time_last_update_
time of the last update
Definition: mrpt_localization_core.h:97
PFLocalizationCore::motion_model_default_options_
CActionRobotMovement2D::TMotionModelOptions motion_model_default_options_
used if there are is not odom
Definition: mrpt_localization_core.h:85
PFLocalizationCore::init_PDF_mode
bool init_PDF_mode
Definition: mrpt_localization_core.h:105
PFLocalizationCore::RUN
@ RUN
Definition: mrpt_localization_core.h:59
PFLocalizationCore::updateFilter
void updateFilter(CActionCollection::Ptr _action, CSensoryFrame::Ptr _sf)
Definition: mrpt_localization_core.cpp:95
PFLocalizationCore::initial_particle_count_
int initial_particle_count_
number of particles for initialization
Definition: mrpt_localization_core.h:96
console.h
PFLocalizationCore::observation
void observation(CSensoryFrame::Ptr _sf, CObservationOdometry::Ptr _odometry)
Definition: mrpt_localization_core.cpp:105
PFLocalizationCore::update_counter_
size_t update_counter_
Definition: mrpt_localization_core.h:99
PFLocalizationCore::motion_model_options_
CActionRobotMovement2D::TMotionModelOptions motion_model_options_
used with odom value motion noise
Definition: mrpt_localization_core.h:87
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
PFLocalizationCore::tictac_
mrpt::system::CTicTac tictac_
timer to measure performance
Definition: mrpt_localization_core.h:98
PFLocalizationCore::pdf_
mrpt::slam::CMonteCarloLocalization2D pdf_
the filter
Definition: mrpt_localization_core.h:93
PFLocalizationCore::INIT
@ INIT
Definition: mrpt_localization_core.h:58
PFLocalizationCore::initial_pose_
mrpt::poses::CPosePDFGaussian initial_pose_
initial posed used in initializeFilter()
Definition: mrpt_localization_core.h:95
PFLocalizationCore::pf_stats_
mrpt::bayes::CParticleFilter::TParticleFilterStats pf_stats_
filter statistics
Definition: mrpt_localization_core.h:92
PFLocalizationCore::use_motion_model_default_options_
bool use_motion_model_default_options_
used default odom_params
Definition: mrpt_localization_core.h:83
PFLocalizationCore::odom_last_observation_
mrpt::poses::CPose2D odom_last_observation_
correct time
Definition: mrpt_localization_core.h:104
std
PFLocalizationCore::PFLocalizationCore
PFLocalizationCore()
Definition: mrpt_localization_core.cpp:50
PFLocalizationCore::init
void init()
Definition: mrpt_localization_core.cpp:51
PFLocalizationCore::metric_map_
CMultiMetricMap::Ptr metric_map_
map
Definition: mrpt_localization_core.h:88
PFLocalizationCore::~PFLocalizationCore
~PFLocalizationCore()
Definition: mrpt_localization_core.cpp:49
ROS_INFO
#define ROS_INFO(...)
PFLocalizationCore::state_
PFStates state_
updates
Definition: mrpt_localization_core.h:101


mrpt_localization
Author(s): Markus Bader, Raphael Zack
autogenerated on Tue Sep 17 2024 02:10:20