mrpt_localization.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 
36 
37 #include <mrpt_bridge/map.h>
38 #include <mrpt/maps/COccupancyGridMap2D.h>
39 #include <mrpt/maps/CSimplePointsMap.h>
42 
43 #include <mrpt/system/filesystem.h>
44 #include <mrpt/opengl/CEllipsoid.h>
46 
47 #include <thread>
48 #include <chrono>
49 
50 using namespace mrpt;
51 using namespace mrpt::slam;
52 using namespace mrpt::opengl;
53 using namespace mrpt::gui;
54 using namespace mrpt::math;
55 using namespace mrpt::system;
56 using namespace mrpt::bayes;
57 using namespace mrpt::poses;
58 using namespace std;
59 
60 #include <mrpt/version.h>
61 using namespace mrpt::maps;
62 using namespace mrpt::obs;
63 
64 #if MRPT_VERSION >= 0x199
65 using namespace mrpt::img;
66 using namespace mrpt::config;
67 #else
68 using namespace mrpt::utils;
69 #endif
70 
73  : PFLocalizationCore(), param_(param)
74 {
75 }
76 
78 {
79  log_info("ini_file ready %s", param_->ini_file.c_str());
81  log_info("ASSERT_FILE_EXISTS_ %s", param_->ini_file.c_str());
82  CConfigFile ini_file;
83  ini_file.setFileName(param_->ini_file);
84  log_info("CConfigFile %s", param_->ini_file.c_str());
85 
86  std::vector<int>
87  particles_count; // Number of initial particles (if size>1, run
88  // the experiments N times)
89 
90  // Load configuration:
91  // -----------------------------------------
92  string iniSectionName("LocalizationExperiment");
93  update_counter_ = 0;
94 
95  // Mandatory entries:
96  ini_file.read_vector(
97  iniSectionName, "particles_count", std::vector<int>(1, 0),
98  particles_count,
99  /*Fail if not found*/ true);
100 
101  if (param_->map_file.empty())
102  {
103  param_->map_file = ini_file.read_string(iniSectionName, "map_file", "");
104  }
105 
106  // Non-mandatory entries:
107  SCENE3D_FREQ_ = ini_file.read_int(iniSectionName, "3DSceneFrequency", 10);
109  ini_file.read_bool(iniSectionName, "3DSceneFollowRobot", true);
110 
112  ini_file.read_bool(iniSectionName, "SHOW_PROGRESS_3D_REAL_TIME", false);
113  SHOW_PROGRESS_3D_REAL_TIME_DELAY_MS_ = ini_file.read_int(
114  iniSectionName, "SHOW_PROGRESS_3D_REAL_TIME_DELAY_MS", 1);
115 
116 #if !MRPT_HAS_WXWIDGETS
118 #endif
119 
120  // Default odometry uncertainty parameters in "odom_params_default_"
121  // depending on how fast the robot moves, etc...
122  // Only used for observations-only rawlogs:
124  CActionRobotMovement2D::mmGaussian;
125 
127  ini_file.read_double("DummyOdometryParams", "minStdXY", 0.04);
129  ini_file.read_double("DefaultOdometryParams", "minStdPHI", 2.0));
130 
131  // Read initial particles distribution; fail if any parameter is not found
132  init_PDF_mode =
133  ini_file.read_bool(iniSectionName, "init_PDF_mode", false, true);
135  ini_file.read_float(iniSectionName, "init_PDF_min_x", 0, true);
137  ini_file.read_float(iniSectionName, "init_PDF_max_x", 0, true);
139  ini_file.read_float(iniSectionName, "init_PDF_min_y", 0, true);
141  ini_file.read_float(iniSectionName, "init_PDF_max_y", 0, true);
142  float min_phi = DEG2RAD(
143  ini_file.read_float(iniSectionName, "init_PDF_min_phi_deg", -180));
144  float max_phi = DEG2RAD(
145  ini_file.read_float(iniSectionName, "init_PDF_max_phi_deg", 180));
148  cov(0, 0) = fabs(init_PDF_max_x - init_PDF_min_x);
149  cov(1, 1) = fabs(init_PDF_max_y - init_PDF_min_y);
150  cov(2, 2) =
151  min_phi < max_phi ? max_phi - min_phi : (max_phi + 2 * M_PI) - min_phi;
152  p.x() = init_PDF_min_x + cov(0, 0) / 2.0;
153  p.y() = init_PDF_min_y + cov(1, 1) / 2.0;
154  p.phi() = min_phi + cov(2, 2) / 2.0;
155  log_debug(
156  "----------- phi: %4.3f: %4.3f <-> %4.3f, %4.3f\n", p.phi(), min_phi,
157  max_phi, cov(2, 2));
159  state_ = INIT;
160 
161  configureFilter(ini_file);
162  // Metric map options:
163 
165  metric_map_, ini_file, param_->map_file, "metricMap",
166  param_->debug))
167  {
168  waitForMap();
169  }
170 
171  initial_particle_count_ = *particles_count.begin();
172 
173  if (param_->gui_mrpt) init3DDebug();
174 }
175 
177 {
178  // PF-algorithm Options:
179  // ---------------------------
181  pfOptions.loadFromConfigFile(_configFile, "PF_options");
182  pfOptions.dumpToConsole();
183 
184  // PDF Options:
185  // ------------------
186  TMonteCarloLocalizationParams pdfPredictionOptions;
187  pdfPredictionOptions.KLD_params.loadFromConfigFile(
188  _configFile, "KLD_options");
189 
190  pdf_.clear();
191 
192  // PDF Options:
193  pdf_.options = pdfPredictionOptions;
194 
196 
197  // Create the PF object:
198  pf_.m_options = pfOptions;
199 }
200 
202 {
203  log_info("init3DDebug");
204  if (!SHOW_PROGRESS_3D_REAL_TIME_) return;
205  if (!win3D_)
206  {
207  win3D_ = CDisplayWindow3D::Create(
208  "pf-localization - The MRPT project", 1000, 600);
209  win3D_->setCameraZoom(20);
210  win3D_->setCameraAzimuthDeg(-45);
211  // win3D_->waitForKey();
212 
213  // Create the 3D scene and get the map only once, later we'll modify
214  // only the particles, etc..
216  // The gridmap:
217 #if MRPT_VERSION >= 0x199
218  if (metric_map_.countMapsByClass<COccupancyGridMap2D>())
219  {
220  metric_map_.mapByClass<COccupancyGridMap2D>()->computeEntropy(
221  grid_info);
222  }
223 #else
225  {
226  metric_map_.m_gridMaps[0]->computeEntropy(grid_info);
227  }
228 #endif
229  else
230  {
233  }
234  log_info(
235  "The gridmap has %.04fm2 observed area, %u observed cells\n",
236  grid_info.effectiveMappedArea,
237  (unsigned)grid_info.effectiveMappedCells);
238  log_info(
239  "Initial PDF: %f particles/m2\n",
241 
242  auto plane = CSetOfObjects::Create();
243  metric_map_.getAs3DObject(plane);
244  scene_.insert(plane);
245 
247  {
248  COpenGLScene::Ptr ptr_scene = win3D_->get3DSceneAndLock();
249 
250  ptr_scene->insert(plane);
251 
252  ptr_scene->enableFollowCamera(true);
253 
254  win3D_->unlockAccess3DScene();
255  }
256  } // Show 3D?
257  if (param_->debug)
258  log_info(" --------------------------- init3DDebug done \n");
259  if (param_->debug) fflush(stdout);
260 }
261 
262 void PFLocalization::show3DDebug(CSensoryFrame::Ptr _observations)
263 {
264  // Create 3D window if requested:
266  {
267  TTimeStamp cur_obs_timestamp = INVALID_TIMESTAMP;
268  if (_observations->size() > 0)
269  cur_obs_timestamp =
270  _observations->getObservationByIndex(0)->timestamp;
271 
272 #if MRPT_VERSION >= 0x199
273  const auto [cov, meanPose] = pdf_.getCovarianceAndMean();
274 #else
275  CPose2D meanPose;
277  pdf_.getCovarianceAndMean(cov, meanPose);
278 #endif
279 
280  COpenGLScene::Ptr ptr_scene = win3D_->get3DSceneAndLock();
281 
282  win3D_->setCameraPointingToPoint(meanPose.x(), meanPose.y(), 0);
283  win3D_->addTextMessage(
284  10, 10,
285  mrpt::format(
286  "timestamp: %s",
287  cur_obs_timestamp != INVALID_TIMESTAMP
288  ? mrpt::system::dateTimeLocalToString(cur_obs_timestamp)
289  .c_str()
290  : "(none)"),
291  TColorf(.8f, .8f, .8f), "mono", 15, mrpt::opengl::NICE, 6001);
292 
293  win3D_->addTextMessage(
294  10, 33,
295  mrpt::format(
296  "#particles= %7u", static_cast<unsigned int>(pdf_.size())),
297  TColorf(.8f, .8f, .8f), "mono", 15, mrpt::opengl::NICE, 6002);
298 
299  win3D_->addTextMessage(
300  10, 55,
301  mrpt::format(
302  "mean pose (x y phi_deg)= %s", meanPose.asString().c_str()),
303  TColorf(.8f, .8f, .8f), "mono", 15, mrpt::opengl::NICE, 6003);
304 
305  // The particles:
306  {
307  CRenderizable::Ptr parts = ptr_scene->getByName("particles");
308  if (parts) ptr_scene->removeObject(parts);
309 
310  CSetOfObjects::Ptr p = pdf_.getAs3DObject<CSetOfObjects::Ptr>();
311  p->setName("particles");
312  ptr_scene->insert(p);
313  }
314 
315  // The particles' cov:
316  {
317  CRenderizable::Ptr ellip = ptr_scene->getByName("parts_cov");
318  if (!ellip)
319  {
320  auto o = CEllipsoid::Create();
321  ellip = o;
322  ellip->setName("parts_cov");
323  ellip->setColor(1, 0, 0, 0.6);
324 
325  o->setLineWidth(2);
326  o->setQuantiles(3);
327  o->set2DsegmentsCount(60);
328  ptr_scene->insert(ellip);
329  }
330  ellip->setLocation(meanPose.x(), meanPose.y(), 0.05);
331 #if MRPT_VERSION >= 0x199
332  dynamic_cast<CEllipsoid*>(ellip.get())->setCovMatrix(cov, 2);
333 #else
334 #endif
336  }
337 
338  // The laser scan:
339  {
340  CRenderizable::Ptr scan_pts = ptr_scene->getByName("scan");
341  if (!scan_pts)
342  {
343  auto o = CPointCloud::Create();
344  scan_pts = o;
345  scan_pts->setName("scan");
346  scan_pts->setColor(1, 0, 0, 0.9);
347  o->enableColorFromZ(false);
348  o->setPointSize(4);
349  ptr_scene->insert(scan_pts);
350  }
351 
352  CSimplePointsMap map;
353  static CSimplePointsMap last_map;
354 
355  CPose3D robot_pose_3D(meanPose);
356 
357  map.clear();
358  _observations->insertObservationsInto(&map);
359 
360  dynamic_cast<CPointCloud*>(scan_pts.get())
361  ->loadFromPointsMap(&last_map);
362  dynamic_cast<CPointCloud*>(scan_pts.get())->setPose(robot_pose_3D);
363  last_map = map;
364  }
365 
366  // The camera:
367  ptr_scene->enableFollowCamera(true);
368 
369  // Views:
370  COpenGLViewport::Ptr view1 = ptr_scene->getViewport("main");
371  {
372  CCamera& cam = view1->getCamera();
373  cam.setAzimuthDegrees(-90);
374  cam.setElevationDegrees(90);
375  cam.setPointingAt(meanPose);
376  cam.setZoomDistance(5);
377  cam.setOrthogonal();
378  }
379 
380  win3D_->unlockAccess3DScene();
381 
382  // Move camera:
383  // win3D_->setCameraPointingToPoint( curRobotPose.x, curRobotPose.y,
384  // curRobotPose.z );
385 
386  // Update:
387  win3D_->forceRepaint();
388 
389  std::this_thread::sleep_for(
390  std::chrono::milliseconds(SHOW_PROGRESS_3D_REAL_TIME_DELAY_MS_));
391  }
392 }
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string &section) MRPT_OVERRIDE
uint64_t TTimeStamp
TMonteCarloLocalizationParams options
CMultiMetricMap metric_map_
map
void setOrthogonal(bool v=true)
bool SHOW_PROGRESS_3D_REAL_TIME_
virtual ~PFLocalization()
mrpt::gui::CDisplayWindow3D::Ptr win3D_
mrpt::opengl::COpenGLScene scene_
void setFileName(const std::string &fil_path)
int SHOW_PROGRESS_3D_REAL_TIME_DELAY_MS_
void getAs3DObject(mrpt::opengl::CSetOfObjectsPtr &outObj) const MRPT_OVERRIDE
int initial_particle_count_
number of particles for initialization
#define M_PI
void setAzimuthDegrees(float ang)
particles_count
struct OBS_IMPEXP mrpt::obs::CActionRobotMovement2D::TMotionModelOptions::TOptions_GaussianModel gaussianModel
void insert(const CRenderizablePtr &newObject, const std::string &viewportName=std::string("main"))
cov
void getAs3DObject(OPENGL_SETOFOBJECTSPTR &out_obj) const
std::string BASE_IMPEXP format(const char *fmt,...) MRPT_printf_format_check(1
double DEG2RAD(const double x)
mrpt::slam::CMonteCarloLocalization2D pdf_
the filter
GLfloat GLfloat p
mrpt::poses::CPosePDFGaussian initial_pose_
initial posed used in initializeFilter()
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string &section) MRPT_OVERRIDE
#define INVALID_TIMESTAMP
CParticleFilter::TParticleFilterOptions m_options
virtual bool waitForMap()
void getCovarianceAndMean(mrpt::math::CMatrixDouble33 &cov, CPose2D &mean_point) const MRPT_OVERRIDE
void setPointingAt(float x, float y, float z)
static const bool loadMap(CMultiMetricMap &_metric_map, const CConfigFile &_config_file, const std::string &_map_file="map.simplemap", const std::string &_section_name="metricMap", bool _debug=false)
void configureFilter(const CConfigFile &_configFile)
void show3DDebug(CSensoryFrame::Ptr _observations)
#define ASSERT_FILE_EXISTS_(FIL)
PFLocalization(Parameters *parm)
GLfloat param
ProxyFilterContainerByClass< mrpt::maps::COccupancyGridMap2DPtr, TListMaps > m_gridMaps
mrpt::bayes::CParticleFilter pf_
common interface for particle filters
std::string BASE_IMPEXP dateTimeLocalToString(const mrpt::system::TTimeStamp t)
CActionRobotMovement2D::TMotionModelOptions motion_model_default_options_
used if there are is not odom
Parameters * param_
void setZoomDistance(float z)
void asString(std::string &s) const
GLdouble GLdouble GLdouble GLdouble GLdouble GLdouble f
void setElevationDegrees(float ang)


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