MRPT  1.9.9
CGraphSlamEngine_impl.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2018, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #ifndef CGRAPHSLAMENGINE_IMPL_H
11 #define CGRAPHSLAMENGINE_IMPL_H
12 
13 #include <mrpt/system/filesystem.h>
15 #include <mrpt/opengl/CAxis.h>
20 
21 namespace mrpt::graphslam
22 {
23 template <class GRAPH_T>
25 template <class GRAPH_T>
27 
28 // Ctors, Dtors implementations
29 //////////////////////////////////////////////////////////////
30 
31 template <class GRAPH_T>
33  const std::string& config_file, const std::string& rawlog_fname /* ="" */,
34  const std::string& fname_GT /* ="" */,
35  mrpt::graphslam::CWindowManager* win_manager /* = NULL */,
37  node_reg /* = NULL */,
39  edge_reg /* = NULL */,
41  optimizer /* = NULL */
42  )
43  : m_node_reg(node_reg),
44  m_edge_reg(edge_reg),
45  m_optimizer(optimizer),
46  m_enable_visuals(win_manager != nullptr),
47  m_config_fname(config_file),
48  m_rawlog_fname(rawlog_fname),
49  m_fname_GT(fname_GT),
50  m_GT_poses_step(1),
51  m_win_manager(win_manager),
52  m_paused_message("Program is paused. Press \"p/P\" to resume."),
53  m_text_index_paused_message(345), // just a large number.
54  m_odometry_color(0, 0, 255),
55  m_GT_color(0, 255, 0),
56  m_estimated_traj_color(255, 165, 0),
57  m_optimized_map_color(255, 0, 0),
58  m_current_constraint_type_color(255, 255, 255),
59  m_robot_model_size(1),
60  m_class_name("CGraphSlamEngine"),
61  m_is_first_time_node_reg(true)
62 {
63  this->initClass();
64 }
65 
66 template <class GRAPH_T>
68 {
69  using namespace mrpt;
70  using namespace std;
71 
73  "In Destructor: Deleting CGraphSlamEngine instance...");
74 
75  // change back the CImage path
76  if (mrpt::system::strCmpI(m_GT_file_format, "rgbd_tum"))
77  {
78  MRPT_LOG_DEBUG_STREAM("Changing back the CImage PATH");
79  mrpt::img::CImage::setImagesPathBase(m_img_prev_path_base);
80  }
81 
82  // delete the CDisplayWindowPlots object
83  if (m_win_plot)
84  {
85  MRPT_LOG_DEBUG_STREAM("Releasing CDisplayWindowPlots...");
86  delete m_win_plot;
87  }
88 }
89 
90 // Member functions implementations
91 //////////////////////////////////////////////////////////////
92 
93 template <class GRAPH_T>
94 typename GRAPH_T::global_pose_t
96 {
97  std::lock_guard<std::mutex> graph_lock(m_graph_section);
98  return m_node_reg->getCurrentRobotPosEstimation();
99 }
100 
101 template <class GRAPH_T>
102 typename GRAPH_T::global_poses_t
104 {
105  std::lock_guard<std::mutex> graph_lock(m_graph_section);
106  return m_graph.nodes;
107 }
108 
109 template <class GRAPH_T>
111  std::set<mrpt::graphs::TNodeID>* nodes_set) const
112 {
113  ASSERTDEB_(nodes_set);
114  m_graph.getAllNodes(*nodes_set);
115 }
116 
117 template <class GRAPH_T>
119 {
120  MRPT_START;
121  using namespace mrpt;
122  using namespace mrpt::opengl;
123  using namespace std;
124 
125  // logger instance properties
126  m_time_logger.setName(m_class_name);
127  this->logging_enable_keep_record = true;
128  this->setLoggerName(m_class_name);
129 
130  // Assert that the deciders/optimizer pointers are valid
131  ASSERTDEB_(m_node_reg);
132  ASSERTDEB_(m_edge_reg);
133  ASSERTDEB_(m_optimizer);
134 
135  // Assert that the graph class used is supported.
136  {
137  MRPT_LOG_INFO_STREAM("Verifying support for given MRPT graph class...");
138 
139  // TODO - initialize vector in a smarter way.
140  m_supported_constraint_types.push_back("CPosePDFGaussianInf");
141  m_supported_constraint_types.push_back("CPose3DPDFGaussianInf");
142 
143  constraint_t c;
144  const string c_str(c.GetRuntimeClass()->className);
145 
146  bool found =
147  (std::find(
148  m_supported_constraint_types.begin(),
149  m_supported_constraint_types.end(),
150  c_str) != m_supported_constraint_types.end());
151 
152  if (found)
153  {
154  MRPT_LOG_INFO_STREAM("[OK] Class: " << c_str);
155  }
156  else
157  {
159  "Given graph class " << c_str
160  << " has not been tested consistently yet."
161  << "Proceed at your own risk.");
163  }
164 
165  // store it in a string for future use.
166  m_current_constraint_type = c_str;
167  m_current_constraint_type = "Constraints: " + m_current_constraint_type;
168  }
169 
170  // If a valid CWindowManager pointer is given then visuals are on.
171  if (m_enable_visuals)
172  {
173  m_win = m_win_manager->win;
174  m_win_observer = m_win_manager->observer;
175  }
176  else
177  {
178  m_win = nullptr;
179  m_win_observer = nullptr;
180 
181  MRPT_LOG_WARN_STREAM("Visualization is off. Running on headless mode");
182  }
183 
184  // set the CDisplayWindowPlots pointer to null for starters, we don't know
185  // if
186  // we are using it
187  m_win_plot = nullptr;
188 
189  m_observation_only_dataset = false;
190  m_request_to_exit = false;
191 
192  // max node number already in the graph
193  m_nodeID_max = INVALID_NODEID;
194 
195  m_is_paused = false;
196  m_GT_poses_index = 0;
197 
198  // pass the necessary variables/objects to the deciders/optimizes
199  // pass a graph ptr after the instance initialization
200  m_node_reg->setGraphPtr(&m_graph);
201  m_edge_reg->setGraphPtr(&m_graph);
202  m_optimizer->setGraphPtr(&m_graph);
203 
204  // pass the window manager pointer
205  // note: m_win_manager contains a pointer to the CDisplayWindow3D instance
206  if (m_enable_visuals)
207  {
208  m_node_reg->setWindowManagerPtr(m_win_manager);
209  m_edge_reg->setWindowManagerPtr(m_win_manager);
210  m_optimizer->setWindowManagerPtr(m_win_manager);
211  m_edge_counter.setWindowManagerPtr(m_win_manager);
212  }
213 
214  // pass a lock in case of multithreaded implementation
215  m_node_reg->setCriticalSectionPtr(&m_graph_section);
216  m_edge_reg->setCriticalSectionPtr(&m_graph_section);
217  m_optimizer->setCriticalSectionPtr(&m_graph_section);
218 
219  // Load the parameters that each one of the self/deciders/optimizer classes
220  // needs
221  this->loadParams(m_config_fname);
222 
223  if (!m_enable_visuals)
224  {
225  MRPT_LOG_WARN_STREAM("Switching all visualization parameters off...");
226  m_visualize_odometry_poses = 0;
227  m_visualize_GT = 0;
228  m_visualize_map = 0;
229  m_visualize_estimated_trajectory = 0;
230  m_visualize_SLAM_metric = 0;
231  m_enable_curr_pos_viewport = 0;
232  m_enable_range_viewport = 0;
233  m_enable_intensity_viewport = 0;
234  }
235 
236  m_use_GT = !m_fname_GT.empty();
237  if (m_use_GT)
238  {
239  if (mrpt::system::strCmpI(m_GT_file_format, "rgbd_tum"))
240  {
241  THROW_EXCEPTION("Not Implemented Yet.");
242  this->alignOpticalWithMRPTFrame();
243  // this->readGTFileRGBD_TUM(m_fname_GT, &m_GT_poses);
244  }
245  else if (mrpt::system::strCmpI(m_GT_file_format, "navsimul"))
246  {
247  this->readGTFile(m_fname_GT, &m_GT_poses);
248  }
249  }
250 
251  // plot the GT related visuals only if ground-truth file is given
252  if (!m_use_GT)
253  {
255  "Ground truth file was not provided. Switching the related "
256  "visualization parameters off...");
257  m_visualize_GT = 0;
258  m_visualize_SLAM_metric = 0;
259  }
260 
261  // timestamp
262  if (m_enable_visuals)
263  {
264  m_win_manager->assignTextMessageParameters(
265  &m_offset_y_timestamp, &m_text_index_timestamp);
266  }
267 
268  if (m_visualize_map)
269  {
270  this->initMapVisualization();
271  }
272 
273  // Configuration of various trajectories visualization
274  ASSERTDEB_(m_has_read_config);
275  if (m_enable_visuals)
276  {
277  // odometry visualization
278  if (m_visualize_odometry_poses)
279  {
280  this->initOdometryVisualization();
281  }
282  // GT Visualization
283  if (m_visualize_GT)
284  {
285  this->initGTVisualization();
286  }
287  // estimated trajectory visualization
288  this->initEstimatedTrajectoryVisualization();
289  // current robot pose viewport
290  if (m_enable_curr_pos_viewport)
291  {
292  this->initCurrPosViewport();
293  }
294  }
295 
296  // change the CImage path in case of RGBD datasets
297  if (mrpt::system::strCmpI(m_GT_file_format, "rgbd_tum"))
298  {
299  // keep the last path - change back to it after rawlog parsing
300  m_img_prev_path_base = mrpt::img::CImage::getImagesPathBase();
301 
302  std::string rawlog_fname_noext =
303  system::extractFileName(m_rawlog_fname);
304  std::string rawlog_dir = system::extractFileDirectory(m_rawlog_fname);
305  m_img_external_storage_dir =
306  rawlog_dir + rawlog_fname_noext + "_Images/";
307  mrpt::img::CImage::setImagesPathBase(m_img_external_storage_dir);
308  }
309 
310  // 3DRangeScans viewports initialization, in case of RGBD datasets
311  if (mrpt::system::strCmpI(m_GT_file_format, "rgbd_tum"))
312  {
313  if (m_enable_range_viewport)
314  {
315  this->initRangeImageViewport();
316  }
317  if (m_enable_intensity_viewport)
318  {
319  this->initIntensityImageViewport();
320  }
321  }
322  // axis
323  if (m_enable_visuals)
324  {
325  COpenGLScene::Ptr scene = m_win->get3DSceneAndLock();
326 
327  CAxis::Ptr obj = mrpt::make_aligned_shared<CAxis>();
328  obj->setFrequency(5);
329  obj->enableTickMarks();
330  obj->setAxisLimits(-10, -10, -10, 10, 10, 10);
331  obj->setName("axis");
332  scene->insert(obj);
333 
334  m_win->unlockAccess3DScene();
335  m_win->forceRepaint();
336  }
337 
338  // Add additional keystrokes in the CDisplayWindow3D help textBox
339  if (m_enable_visuals)
340  {
341  // keystrokes initialization
342  m_keystroke_pause_exec = "p";
343  m_keystroke_odometry = "o";
344  m_keystroke_GT = "g";
345  m_keystroke_estimated_trajectory = "t";
346  m_keystroke_map = "m";
347 
348  // keystrokes registration
349  m_win_observer->registerKeystroke(
350  m_keystroke_pause_exec, "Pause/Resume program execution");
351  m_win_observer->registerKeystroke(
352  m_keystroke_odometry, "Toggle Odometry visualization");
353  m_win_observer->registerKeystroke(
354  m_keystroke_GT, "Toggle Ground-Truth visualization");
355  m_win_observer->registerKeystroke(
356  m_keystroke_estimated_trajectory,
357  "Toggle Estimated trajectory visualization");
358  m_win_observer->registerKeystroke(
359  m_keystroke_map, "Toggle Map visualization");
360  }
361 
362  // register the types of edges
363  vector<string> vec_edge_types;
364  vec_edge_types.push_back("Odometry");
365  vec_edge_types.push_back("ICP2D");
366  vec_edge_types.push_back("ICP3D");
367 
368  for (vector<string>::const_iterator cit = vec_edge_types.begin();
369  cit != vec_edge_types.end(); ++cit)
370  {
371  m_edge_counter.addEdgeType(*cit);
372  }
373 
374  // Visualize the edge statistics
375  if (m_enable_visuals)
376  {
377  // total edges - loop closure edges
378  double offset_y_total_edges, offset_y_loop_closures;
379  int text_index_total_edges, text_index_loop_closures;
380 
381  m_win_manager->assignTextMessageParameters(
382  &offset_y_total_edges, &text_index_total_edges);
383 
384  // build each one of these
385  map<string, double> name_to_offset_y;
386  map<string, int> name_to_text_index;
387  for (vector<string>::const_iterator it = vec_edge_types.begin();
388  it != vec_edge_types.end(); ++it)
389  {
390  m_win_manager->assignTextMessageParameters(
391  &name_to_offset_y[*it], &name_to_text_index[*it]);
392  }
393 
394  m_win_manager->assignTextMessageParameters(
395  &offset_y_loop_closures, &text_index_loop_closures);
396 
397  // add all the parameters to the CEdgeCounter object
398  m_edge_counter.setTextMessageParams(
399  name_to_offset_y, name_to_text_index, offset_y_total_edges,
400  text_index_total_edges, offset_y_loop_closures,
401  text_index_loop_closures);
402  }
403 
404  // Type of the generated graph
405  if (m_enable_visuals)
406  {
407  m_win_manager->assignTextMessageParameters(
408  &m_offset_y_current_constraint_type,
409  &m_text_index_current_constraint_type);
410  m_win_manager->addTextMessage(
411  m_offset_x_left, -m_offset_y_current_constraint_type,
412  m_current_constraint_type,
413  mrpt::img::TColorf(m_current_constraint_type_color),
414  m_text_index_current_constraint_type);
415  }
416 
417  // query node/edge deciders for visual objects initialization
418  if (m_enable_visuals)
419  {
420  std::lock_guard<std::mutex> graph_lock(m_graph_section);
421  m_time_logger.enter("Visuals");
422  m_node_reg->initializeVisuals();
423  m_edge_reg->initializeVisuals();
424  m_optimizer->initializeVisuals();
425  m_time_logger.leave("Visuals");
426  }
427 
428  m_init_timestamp = INVALID_TIMESTAMP;
429 
430  // COccupancyGridMap2D Initialization
431  {
433  mrpt::make_aligned_shared<mrpt::maps::COccupancyGridMap2D>();
434 
435  gridmap->setSize(
436  /* min_x = */ -20.0f,
437  /* float max_x = */ 20.0f,
438  /* float min_y = */ -20.0f,
439  /* float max_y = */ 20.0f,
440  /* float resolution = */ 0.05f);
441 
442  // TODO - Read these from the .ini file
443  // observation insertion options
444  gridmap->insertionOptions.maxOccupancyUpdateCertainty = 0.8f;
445  gridmap->insertionOptions.maxDistanceInsertion = 5;
446  gridmap->insertionOptions.wideningBeamsWithDistance = true;
447  gridmap->insertionOptions.decimation = 2;
448 
449  m_gridmap_cached = gridmap;
450  m_map_is_cached = false;
451  }
452 
453  // COctoMap Initialization
454  {
456  mrpt::make_aligned_shared<mrpt::maps::COctoMap>();
457 
458  // TODO - adjust the insertionoptions...
459  // TODO - Read these from the .ini file
460  octomap->insertionOptions.setOccupancyThres(0.5);
461  octomap->insertionOptions.setProbHit(0.7);
462  octomap->insertionOptions.setProbMiss(0.4);
463  octomap->insertionOptions.setClampingThresMin(0.1192);
464  octomap->insertionOptions.setClampingThresMax(0.971);
465 
466  m_octomap_cached = octomap;
467  m_map_is_cached = false;
468  }
469 
470  // In case we are given an RGBD TUM Dataset - try and read the info file so
471  // that we know how to play back the GT poses.
472  try
473  {
474  m_info_params.setRawlogFile(m_rawlog_fname);
475  m_info_params.parseFile();
476  // set the rate at which we read from the GT poses vector
477  int num_of_objects = std::atoi(
478  m_info_params.fields["Overall number of objects"].c_str());
479  m_GT_poses_step = m_GT_poses.size() / num_of_objects;
480 
482  "Overall number of objects in rawlog: " << num_of_objects);
484  "Setting the Ground truth read step to: " << m_GT_poses_step);
485  }
486  catch (std::exception& e)
487  {
488  MRPT_LOG_INFO_STREAM("RGBD_TUM info file was not found: " << e.what());
489  }
490 
491  // SLAM evaluation metric
492  m_curr_deformation_energy = 0;
493  if (m_visualize_SLAM_metric)
494  {
495  this->initSlamMetricVisualization();
496  }
497 
498  // Message to be displayed on pause
499  if (m_enable_visuals)
500  {
501  this->m_win->addTextMessage(
502  0.5, 0.3, "", mrpt::img::TColorf(1.0, 0, 0),
503  m_text_index_paused_message);
504  }
505 
506  MRPT_END;
507 } // end of initClass
508 
509 template <class GRAPH_T>
511  mrpt::obs::CObservation::Ptr& observation, size_t& rawlog_entry)
512 {
513  using namespace mrpt::obs;
514 
515  CActionCollection::Ptr action;
516  CSensoryFrame::Ptr observations;
517 
518  return this->_execGraphSlamStep(
519  action, observations, observation, rawlog_entry);
520 } // end of execGraphSlamStep
521 
522 template <class GRAPH_T>
525  mrpt::obs::CSensoryFrame::Ptr& observations,
526  mrpt::obs::CObservation::Ptr& observation, size_t& rawlog_entry)
527 {
528  MRPT_START;
529 
530  using namespace std;
531  using namespace mrpt;
532  using namespace mrpt::poses;
533  using namespace mrpt::obs;
534  using namespace mrpt::obs::utils;
535  using namespace mrpt::opengl;
536  using namespace mrpt::system;
537 
538  m_time_logger.enter("proc_time");
539 
541  m_has_read_config,
542  format("\nConfig file is not read yet.\nExiting... \n"));
543  // good to go..
544 
545  // read first measurement independently if we haven't already
546  if (m_init_timestamp == INVALID_TIMESTAMP)
547  {
548  m_init_timestamp = getTimeStamp(action, observations, observation);
549  MRPT_LOG_DEBUG_STREAM("execGraphSlamStep: first run");
550 
551  if (observation)
552  {
553  MRPT_LOG_DEBUG_STREAM("Observation only dataset!");
554  m_observation_only_dataset = true; // false by default
555  }
556  else
557  {
558  MRPT_LOG_DEBUG_STREAM("Action-observation dataset!");
559  ASSERTDEB_(action);
560  m_observation_only_dataset = false;
561 
562  CPose3D increment_pose_3d;
563  action->getFirstMovementEstimationMean(increment_pose_3d);
564  pose_t increment_pose(increment_pose_3d);
565  m_curr_odometry_only_pose += increment_pose;
566  }
567 
568  // TODO enable this and test this.
569  // return true;
570  }
571 
572  // NRD
573  bool registered_new_node;
574  {
575  std::lock_guard<std::mutex> graph_lock(m_graph_section);
576  m_time_logger.enter("node_registrar");
577  registered_new_node =
578  m_node_reg->updateState(action, observations, observation);
579  m_time_logger.leave("node_registrar");
580  }
581 
582  { // get the 2D laser scan, if there
584  getObservation<CObservation2DRangeScan>(observations, observation);
585  if (scan)
586  {
587  m_last_laser_scan2D = scan;
588 
589  if (!m_first_laser_scan2D)
590  { // capture first laser scan seperately
591  m_first_laser_scan2D = m_last_laser_scan2D;
592  }
593  }
594  }
595 
596  if (registered_new_node)
597  {
598  // At the first node registration, must have registered exactly 2 nodes
599  // (root + first)
600  if (m_is_first_time_node_reg)
601  {
602  std::lock_guard<std::mutex> graph_lock(m_graph_section);
603  m_nodeID_max = 0;
604  if (m_graph.nodeCount() != 2)
605  {
607  "Expected [2] new registered nodes"
608  << " but got [" << m_graph.nodeCount() << "]");
609  THROW_EXCEPTION(format("Illegal node registration"));
610  }
611 
612  m_nodes_to_laser_scans2D.insert(
613  make_pair(m_nodeID_max, m_first_laser_scan2D));
614 
615  m_is_first_time_node_reg = false;
616  }
617 
618  // going to be incremented in monitorNodeRegistration anyway.
619  m_nodeID_max++;
620 
621  // either way add just one odometry edge
622  m_edge_counter.addEdge("Odometry");
623  }
624  this->monitorNodeRegistration(
625  registered_new_node, "NodeRegistrationDecider");
626 
627  // Edge registration procedure - Optimization
628  // run this so that the ERD, GSO can be updated with the latest
629  // observations even when no new nodes have been added to the graph
630  { // ERD
631  std::lock_guard<std::mutex> graph_lock(m_graph_section);
632 
633  m_time_logger.enter("edge_registrar");
634  m_edge_reg->updateState(action, observations, observation);
635  m_time_logger.leave("edge_registrar");
636  }
637  this->monitorNodeRegistration(
638  registered_new_node, "EdgeRegistrationDecider");
639 
640  { // GSO
641  std::lock_guard<std::mutex> graph_lock(m_graph_section);
642 
643  m_time_logger.enter("optimizer");
644  m_optimizer->updateState(action, observations, observation);
645  m_time_logger.leave("optimizer");
646  }
647  this->monitorNodeRegistration(registered_new_node, "GraphSlamOptimizer");
648 
649  // current timestamp - to be filled depending on the format
650  m_curr_timestamp = getTimeStamp(action, observations, observation);
651 
652  if (observation)
653  {
654  // Read a single observation from the rawlog
655  // (Format #2 rawlog file)
656 
657  // odometry
658  if (IS_CLASS(observation, CObservationOdometry))
659  {
660  CObservationOdometry::Ptr obs_odometry =
661  std::dynamic_pointer_cast<CObservationOdometry>(observation);
662 
663  m_curr_odometry_only_pose = pose_t(obs_odometry->odometry);
664  m_odometry_poses.push_back(m_curr_odometry_only_pose);
665  }
666  else if (IS_CLASS(observation, CObservation3DRangeScan))
667  {
668  m_last_laser_scan3D =
669  std::dynamic_pointer_cast<mrpt::obs::CObservation3DRangeScan>(
670  observation);
671  }
672  }
673  else
674  {
675  // action, observations should contain a pair of valid data
676  // (Format #1 rawlog file)
677  ASSERTDEB_(observations);
678  ASSERTDEB_(action);
679 
680  CPose3D increment_pose_3d;
681  action->getFirstMovementEstimationMean(increment_pose_3d);
682  pose_t increment_pose(increment_pose_3d);
683  m_curr_odometry_only_pose += increment_pose;
684  m_odometry_poses.push_back(m_curr_odometry_only_pose);
685  } // ELSE FORMAT #1 - Action/Observations
686 
687  if (registered_new_node)
688  {
689  this->execDijkstraNodesEstimation();
690 
691  // keep track of the laser scans so that I can later visualize the map
692  m_nodes_to_laser_scans2D[m_nodeID_max] = m_last_laser_scan2D;
693 
694  if (m_enable_visuals && m_visualize_map)
695  {
696  std::lock_guard<std::mutex> graph_lock(m_graph_section);
697  // bool full_update = m_optimizer->justFullyOptimizedGraph();
698  bool full_update = true;
699  this->updateMapVisualization(m_nodes_to_laser_scans2D, full_update);
700  }
701 
702  // query node/edge deciders for visual objects update
703  if (m_enable_visuals)
704  {
705  this->updateAllVisuals();
706  }
707 
708  // update the edge counter
709  std::map<std::string, int> edge_types_to_nums;
710  m_edge_reg->getEdgesStats(&edge_types_to_nums);
711  if (edge_types_to_nums.size())
712  {
714  edge_types_to_nums.begin();
715  it != edge_types_to_nums.end(); ++it)
716  {
717  // loop closure
718  if (mrpt::system::strCmpI(it->first, "lc"))
719  {
720  m_edge_counter.setLoopClosureEdgesManually(it->second);
721  }
722  else
723  {
724  m_edge_counter.setEdgesManually(it->first, it->second);
725  }
726  }
727  }
728 
729  // update the graph visualization
730 
731  if (m_enable_curr_pos_viewport)
732  {
733  updateCurrPosViewport();
734  }
735  // update visualization of estimated trajectory
736  if (m_enable_visuals)
737  {
738  bool full_update = true; // don't care, do it anyway.
739  m_time_logger.enter("Visuals");
740  this->updateEstimatedTrajectoryVisualization(full_update);
741  m_time_logger.leave("Visuals");
742  }
743 
744  // refine the SLAM metric and update its corresponding visualization
745  // This is done only when the GT is available.
746  if (m_use_GT)
747  {
748  m_time_logger.enter("SLAM_metric");
749  this->computeSlamMetric(m_nodeID_max, m_GT_poses_index);
750  m_time_logger.leave("SLAM_metric");
751  if (m_visualize_SLAM_metric)
752  {
753  m_time_logger.enter("Visuals");
754  this->updateSlamMetricVisualization();
755  m_time_logger.leave("Visuals");
756  }
757  }
758 
759  // mark the map outdated
760  m_map_is_cached = false;
761 
762  } // IF REGISTERED_NEW_NODE
763 
764  //
765  // Visualization related actions
766  //
767  m_time_logger.enter("Visuals");
768  // Timestamp textMessage
769  // Use the dataset timestamp otherwise fallback to
770  // mrpt::system::getCurrentTime
771  if (m_enable_visuals)
772  {
773  if (m_curr_timestamp != INVALID_TIMESTAMP)
774  {
775  m_win_manager->addTextMessage(
776  m_offset_x_left, -m_offset_y_timestamp,
777  format(
778  "Simulated time: %s",
779  timeToString(m_curr_timestamp).c_str()),
780  mrpt::img::TColorf(1.0, 1.0, 1.0),
781  /* unique_index = */ m_text_index_timestamp);
782  }
783  else
784  {
785  m_win_manager->addTextMessage(
786  m_offset_x_left, -m_offset_y_timestamp,
787  format(
788  "Wall time: %s",
790  mrpt::img::TColorf(1.0, 1.0, 1.0),
791  /* unique_index = */ m_text_index_timestamp);
792  }
793  }
794 
795  // Odometry visualization
796  if (m_visualize_odometry_poses && m_odometry_poses.size())
797  {
798  this->updateOdometryVisualization();
799  }
800 
801  // ensure that the GT is visualized at the same rate as the SLAM procedure
802  // handle RGBD-TUM datasets manually. Advance the GT index accordingly
803  if (m_use_GT)
804  {
805  if (mrpt::system::strCmpI(m_GT_file_format, "rgbd_tum"))
806  { // 1/loop
807  if (m_enable_visuals)
808  {
809  this->updateGTVisualization(); // I have already taken care of
810  // the step
811  }
812  m_GT_poses_index += m_GT_poses_step;
813  }
814  else if (mrpt::system::strCmpI(m_GT_file_format, "navsimul"))
815  {
816  if (m_observation_only_dataset)
817  { // 1/2loops
818  if (rawlog_entry % 2 == 0)
819  {
820  if (m_enable_visuals)
821  {
822  this->updateGTVisualization(); // I have already taken
823  // care of the step
824  }
825  m_GT_poses_index += m_GT_poses_step;
826  }
827  }
828  else
829  { // 1/loop
830  // get both action and observation at a single step - same rate
831  // as GT
832  if (m_enable_visuals)
833  {
834  this->updateGTVisualization(); // I have already taken care
835  // of the step
836  }
837  m_GT_poses_index += m_GT_poses_step;
838  }
839  }
840  }
841 
842  // 3DRangeScans viewports update
843  if (mrpt::system::strCmpI(m_GT_file_format, "rgbd_tum"))
844  {
845  if (m_enable_range_viewport && m_last_laser_scan3D)
846  {
847  this->updateRangeImageViewport();
848  }
849 
850  if (m_enable_intensity_viewport && m_last_laser_scan3D)
851  {
852  this->updateIntensityImageViewport();
853  }
854  }
855 
856  // Query for events and take corresponding actions
857  if (m_enable_visuals)
858  {
859  this->queryObserverForEvents();
860  }
861  m_time_logger.leave("Visuals");
862 
863  m_dataset_grab_time =
864  mrpt::system::timeDifference(m_init_timestamp, m_curr_timestamp);
865  m_time_logger.leave("proc_time");
866 
867  return !m_request_to_exit;
868  MRPT_END;
869 } // end of _execGraphSlamStep
870 
871 template <class GRAPH_T>
873 {
874  {
875  std::lock_guard<std::mutex> graph_lock(m_graph_section);
876  m_time_logger.enter("dijkstra_nodes_estimation");
877  m_graph.dijkstra_nodes_estimate();
878  m_time_logger.leave("dijkstra_nodes_estimation");
879  }
880 }
881 
882 template <class GRAPH_T>
884  bool registered /*=false*/, std::string class_name /*="Class"*/)
885 {
886  MRPT_START;
887  using namespace mrpt;
888 
889  std::lock_guard<std::mutex> graph_lock(m_graph_section);
890  size_t listed_nodeCount =
891  (m_nodeID_max == INVALID_NODEID ? 0 : m_nodeID_max + 1);
892 
893  if (!registered)
894  { // just check that it's the same.
896  listed_nodeCount == m_graph.nodeCount(),
897  format(
898  "listed_nodeCount [%lu] != nodeCount() [%lu]",
899  static_cast<unsigned long>(listed_nodeCount),
900  static_cast<unsigned long>(m_graph.nodeCount())));
901  }
902  else
903  {
904  if (listed_nodeCount != m_graph.nodeCount())
905  {
907  class_name << " illegally added new nodes to the graph "
908  << ", wanted to see [" << listed_nodeCount
909  << "] but saw [" << m_graph.nodeCount() << "]");
911  format("Illegal node registration by %s.", class_name.c_str()));
912  }
913  }
914  MRPT_END;
915 }
916 
917 template <class GRAPH_T>
920  mrpt::system::TTimeStamp* acquisition_time /*=NULL*/) const
921 {
922  MRPT_START;
923 
924  if (!map)
925  {
926  map = mrpt::make_aligned_shared<mrpt::maps::COccupancyGridMap2D>();
927  }
928  ASSERTDEB_(map);
929 
930  if (!m_map_is_cached)
931  {
932  this->computeMap();
933  }
934  map->copyMapContentFrom(*m_gridmap_cached);
935 
936  // fill the timestamp if this is given
937  if (acquisition_time)
938  {
939  *acquisition_time = m_map_acq_time;
940  }
941  MRPT_END;
942 }
943 
944 template <class GRAPH_T>
947  mrpt::system::TTimeStamp* acquisition_time /*=NULL*/) const
948 {
949  MRPT_START;
950  THROW_EXCEPTION("Not Implemented Yet.");
951 
952  if (!m_map_is_cached)
953  {
954  this->computeMap();
955  }
956  // map =
957  // dynamic_cast<mrpt::maps::COctoMap::Ptr>(m_octomap_cached->clone());
958  ASSERTDEB_(map);
959 
960  // fill the timestamp if this is given
961  if (acquisition_time)
962  {
963  *acquisition_time = m_map_acq_time;
964  }
965 
966  MRPT_END;
967 }
968 
969 template <class GRAPH_T>
971 {
972  MRPT_START;
973  using namespace std;
974  using namespace mrpt;
975  using namespace mrpt::maps;
976  using namespace mrpt::poses;
977 
978  std::lock_guard<std::mutex> graph_lock(m_graph_section);
979 
980  if (!constraint_t::is_3D())
981  { // 2D Poses
982  // MRPT_LOG_DEBUG_STREAM("Computing the occupancy gridmap...");
983  mrpt::maps::COccupancyGridMap2D::Ptr gridmap = m_gridmap_cached;
984  gridmap->clear();
985 
986  // traverse all the nodes - add their laser scans at their corresponding
987  // poses
988  for (std::map<
991  m_nodes_to_laser_scans2D.begin();
992  it != m_nodes_to_laser_scans2D.end(); ++it)
993  {
994  const mrpt::graphs::TNodeID& curr_node = it->first;
995 
996  // fetch LaserScan
997  const mrpt::obs::CObservation2DRangeScan::Ptr& curr_laser_scan =
998  it->second;
1000  curr_laser_scan, format(
1001  "LaserScan of nodeID: %lu is not present.",
1002  static_cast<unsigned long>(curr_node)));
1003 
1004  // Fetch pose at which to display the LaserScan
1005  CPose3D scan_pose = getLSPoseForGridMapVisualization(curr_node);
1006 
1007  // Add all to gridmap
1008  gridmap->insertObservation(curr_laser_scan.get(), &scan_pose);
1009  }
1010 
1011  m_map_is_cached = true;
1012  m_map_acq_time = mrpt::system::now();
1013  }
1014  else
1015  { // 3D Pose
1016  // MRPT_LOG_DEBUG_STREAM("Computing the Octomap...");
1017  THROW_EXCEPTION("Not Implemented Yet. Method is to compute a COctoMap");
1018  // MRPT_LOG_DEBUG_STREAM("Computed COctoMap successfully.");
1019  }
1020 
1021  MRPT_END;
1022 } // end of computeMap
1023 
1024 template <class GRAPH_T>
1026 {
1027  MRPT_START;
1028 
1029  ASSERTDEBMSG_(
1030  mrpt::system::fileExists(fname),
1031  mrpt::format("\nConfiguration file not found: \n%s\n", fname.c_str()));
1032 
1033  MRPT_LOG_INFO_STREAM("Reading the .ini file... ");
1034  MRPT_LOG_INFO_STREAM("Reading the .ini file... ");
1035  mrpt::config::CConfigFile cfg_file(fname);
1036 
1037  // Section: GeneralConfiguration
1038  // ////////////////////////////////
1039  m_user_decides_about_output_dir = cfg_file.read_bool(
1040  "GeneralConfiguration", "user_decides_about_output_dir", false, false);
1041  m_GT_file_format = cfg_file.read_string(
1042  "GeneralConfiguration", "ground_truth_file_format", "NavSimul", false);
1043 
1044  // Minimum verbosity level of the logger
1045  int min_verbosity_level =
1046  cfg_file.read_int("GeneralConfiguration", "class_verbosity", 1, false);
1047  this->setMinLoggingLevel(mrpt::system::VerbosityLevel(min_verbosity_level));
1048 
1049  // Section: VisualizationParameters
1050  // ////////////////////////////////
1051 
1052  // map visualization
1053  m_visualize_map = cfg_file.read_bool(
1054  "VisualizationParameters", "visualize_map", true, false);
1055 
1056  // odometry-only visualization
1057  m_visualize_odometry_poses = cfg_file.read_bool(
1058  "VisualizationParameters", "visualize_odometry_poses", true, false);
1059  m_visualize_estimated_trajectory = cfg_file.read_bool(
1060  "VisualizationParameters", "visualize_estimated_trajectory", true,
1061  false);
1062 
1063  // GT configuration visualization
1064  m_visualize_GT = cfg_file.read_bool(
1065  "VisualizationParameters", "visualize_ground_truth", true, false);
1066  // SLAM metric plot
1067  m_visualize_SLAM_metric = cfg_file.read_bool(
1068  "VisualizationParameters", "visualize_SLAM_metric", true, false);
1069 
1070  // Viewports flags
1071  m_enable_curr_pos_viewport = cfg_file.read_bool(
1072  "VisualizationParameters", "enable_curr_pos_viewport", true, false);
1073  m_enable_range_viewport = cfg_file.read_bool(
1074  "VisualizationParameters", "enable_range_viewport", false, false);
1075  m_enable_intensity_viewport = cfg_file.read_bool(
1076  "VisualizationParameters", "enable_intensity_viewport", false, false);
1077 
1078  m_node_reg->loadParams(fname);
1079  m_edge_reg->loadParams(fname);
1080  m_optimizer->loadParams(fname);
1081 
1082  m_has_read_config = true;
1083  MRPT_END;
1084 }
1085 template <class GRAPH_T>
1087 {
1088  MRPT_START;
1089 
1090  std::string str;
1091  this->getParamsAsString(&str);
1092  return str;
1093 
1094  MRPT_END;
1095 }
1096 template <class GRAPH_T>
1098 {
1099  MRPT_START;
1100  ASSERTDEB_(m_has_read_config);
1101  using namespace std;
1102 
1103  stringstream ss_out;
1104 
1105  ss_out
1106  << "\n------------[ Graphslam_engine Problem Parameters ]------------"
1107  << std::endl;
1108  ss_out << "Config filename = " << m_config_fname
1109  << std::endl;
1110 
1111  ss_out << "Ground Truth File format = " << m_GT_file_format
1112  << std::endl;
1113  ss_out << "Ground Truth filename = " << m_fname_GT << std::endl;
1114 
1115  ss_out << "Visualize odometry = "
1116  << (m_visualize_odometry_poses ? "TRUE" : "FALSE") << std::endl;
1117  ss_out << "Visualize estimated trajectory = "
1118  << (m_visualize_estimated_trajectory ? "TRUE" : "FALSE")
1119  << std::endl;
1120  ss_out << "Visualize map = "
1121  << (m_visualize_map ? "TRUE" : "FALSE") << std::endl;
1122  ss_out << "Visualize Ground Truth = "
1123  << (m_visualize_GT ? "TRUE" : "FALSE") << std::endl;
1124 
1125  ss_out << "Visualize SLAM metric plot = "
1126  << (m_visualize_SLAM_metric ? "TRUE" : "FALSE") << std::endl;
1127 
1128  ss_out << "Enable curr. position viewport = "
1129  << (m_enable_curr_pos_viewport ? "TRUE" : "FALSE") << endl;
1130  ss_out << "Enable range img viewport = "
1131  << (m_enable_range_viewport ? "TRUE" : "FALSE") << endl;
1132  ss_out << "Enable intensity img viewport = "
1133  << (m_enable_intensity_viewport ? "TRUE" : "FALSE") << endl;
1134 
1135  ss_out << "-----------------------------------------------------------"
1136  << std::endl;
1137  ss_out << std::endl;
1138 
1139  // copy the stringstream contents to the passed in string
1140  *params_out = ss_out.str();
1141 
1142  MRPT_END;
1143 }
1144 
1145 template <class GRAPH_T>
1147 {
1148  MRPT_START;
1149  std::cout << getParamsAsString();
1150 
1151  m_node_reg->printParams();
1152  m_edge_reg->printParams();
1153  m_optimizer->printParams();
1154 
1155  MRPT_END;
1156 }
1157 
1158 template <class GRAPH_T>
1160 {
1161  MRPT_START;
1162  using namespace std;
1163  using namespace mrpt::system;
1164 
1165  MRPT_LOG_INFO_STREAM("Setting up file: " << fname);
1166 
1167  // current time vars
1169  std::string time_spec = "UTC Time";
1170  string cur_date_str(dateTimeToString(cur_date));
1171  string cur_date_validstr(fileNameStripInvalidChars(cur_date_str));
1172 
1173  m_out_streams[fname].open(fname);
1174  ASSERTDEBMSG_(
1175  m_out_streams[fname].fileOpenCorrectly(),
1176  mrpt::format("\nError while trying to open %s\n", fname.c_str()));
1177 
1178  const std::string sep(80, '#');
1179 
1180  m_out_streams[fname].printf("# Mobile Robot Programming Toolkit (MRPT)\n");
1181  m_out_streams[fname].printf("# http::/www.mrpt.org\n");
1182  m_out_streams[fname].printf("# GraphSlamEngine Application\n");
1183  m_out_streams[fname].printf(
1184  "# Automatically generated file - %s: %s\n", time_spec.c_str(),
1185  cur_date_str.c_str());
1186  m_out_streams[fname].printf("%s\n\n", sep.c_str());
1187 
1188  MRPT_END;
1189 }
1190 
1191 template <class GRAPH_T>
1193 {
1194  MRPT_START;
1195  ASSERTDEB_(m_enable_visuals);
1196  using namespace mrpt::opengl;
1197 
1198  COpenGLScene::Ptr scene = m_win->get3DSceneAndLock();
1199  COpenGLViewport::Ptr viewp_range;
1200 
1201  viewp_range = scene->createViewport("viewp_range");
1202  double x, y, h, w;
1203  m_win_manager->assignViewportParameters(&x, &y, &w, &h);
1204  viewp_range->setViewportPosition(x, y, h, w);
1205 
1206  m_win->unlockAccess3DScene();
1207  m_win->forceRepaint();
1208 
1209  MRPT_END;
1210 }
1211 
1212 template <class GRAPH_T>
1214 {
1215  MRPT_START;
1216  std::lock_guard<std::mutex> graph_lock(m_graph_section);
1217  m_time_logger.enter("Visuals");
1218 
1219  m_node_reg->updateVisuals();
1220  m_edge_reg->updateVisuals();
1221  m_optimizer->updateVisuals();
1222 
1223  m_time_logger.leave("Visuals");
1224  MRPT_END;
1225 }
1226 
1227 template <class GRAPH_T>
1229 {
1230  MRPT_START;
1231  ASSERTDEB_(m_enable_visuals);
1232  using namespace mrpt::math;
1233  using namespace mrpt::opengl;
1234 
1235  if (m_last_laser_scan3D->hasRangeImage)
1236  {
1237  // TODO - make this a static class member - or at least a private member
1238  // of the class
1239  CMatrixFloat range2D;
1241 
1242  // load the image if not already loaded..
1243  m_last_laser_scan3D->load();
1244  range2D = m_last_laser_scan3D->rangeImage *
1245  (1.0f / 5.0); // TODO - without the magic number?
1246  img.setFromMatrix(range2D);
1247 
1248  COpenGLScene::Ptr scene = m_win->get3DSceneAndLock();
1249  COpenGLViewport::Ptr viewp_range = scene->getViewport("viewp_range");
1250  viewp_range->setImageView(img);
1251  m_win->unlockAccess3DScene();
1252  m_win->forceRepaint();
1253  }
1254 
1255  MRPT_END;
1256 }
1257 
1258 template <class GRAPH_T>
1260 {
1261  MRPT_START;
1262  ASSERTDEB_(m_enable_visuals);
1263  using namespace mrpt::opengl;
1264 
1265  COpenGLScene::Ptr scene = m_win->get3DSceneAndLock();
1266  COpenGLViewport::Ptr viewp_intensity;
1267 
1268  viewp_intensity = scene->createViewport("viewp_intensity");
1269  double x, y, w, h;
1270  m_win_manager->assignViewportParameters(&x, &y, &w, &h);
1271  viewp_intensity->setViewportPosition(x, y, w, h);
1272 
1273  m_win->unlockAccess3DScene();
1274  m_win->forceRepaint();
1275 
1276  MRPT_END;
1277 }
1278 template <class GRAPH_T>
1280 {
1281  MRPT_START;
1282  ASSERTDEB_(m_enable_visuals);
1283  using namespace mrpt::opengl;
1284 
1285  if (m_last_laser_scan3D->hasIntensityImage)
1286  {
1288 
1289  // load the image if not already loaded..
1290  m_last_laser_scan3D->load();
1291  img = m_last_laser_scan3D->intensityImage;
1292 
1293  COpenGLScene::Ptr scene = m_win->get3DSceneAndLock();
1294  COpenGLViewport::Ptr viewp_intensity =
1295  scene->getViewport("viewp_intensity");
1296  viewp_intensity->setImageView(img);
1297  m_win->unlockAccess3DScene();
1298  m_win->forceRepaint();
1299  }
1300 
1301  MRPT_END;
1302 } // end of updateIntensityImageViewport
1303 
1304 template <class GRAPH_T>
1307 {
1308  pose_t p;
1309  return this->initRobotModelVisualizationInternal(p);
1310 } // end of initRobotModelVisualization
1311 
1312 template <class GRAPH_T>
1315  const mrpt::poses::CPose2D& p_unused)
1316 {
1318 
1319 } // end of initRobotModelVisualizationInternal - CPose2D
1320 
1321 template <class GRAPH_T>
1324  const mrpt::poses::CPose3D& p_unused)
1325 {
1327 } // end of initRobotModelVisualizationInternal - CPose3D
1328 
1329 template <class GRAPH_T>
1331 {
1332  MRPT_START;
1333  ASSERTDEB_(m_enable_visuals);
1334  using namespace mrpt::opengl;
1335 
1336  COpenGLScene::Ptr scene = m_win->get3DSceneAndLock();
1337  COpenGLViewport::Ptr viewp =
1338  scene->createViewport("curr_robot_pose_viewport");
1339  // Add a clone viewport, using [0,1] factor X,Y,Width,Height coordinates:
1340  viewp->setCloneView("main");
1341  double x, y, h, w;
1342  m_win_manager->assignViewportParameters(&x, &y, &w, &h);
1343  viewp->setViewportPosition(x, y, h, w);
1344  viewp->setTransparent(false);
1345  viewp->getCamera().setAzimuthDegrees(90);
1346  viewp->getCamera().setElevationDegrees(90);
1347  viewp->setCustomBackgroundColor(
1348  mrpt::img::TColorf(205, 193, 197, /*alpha = */ 255));
1349  viewp->getCamera().setZoomDistance(30);
1350  viewp->getCamera().setOrthogonal();
1351 
1352  m_win->unlockAccess3DScene();
1353  m_win->forceRepaint();
1354 
1355  MRPT_END;
1356 }
1357 
1358 template <class GRAPH_T>
1360 {
1361  MRPT_START;
1362  ASSERTDEB_(m_enable_visuals);
1363  using namespace mrpt::opengl;
1364  using namespace mrpt::poses;
1365 
1366  ASSERTDEB_(m_enable_visuals);
1367 
1368  global_pose_t curr_robot_pose = this->getCurrentRobotPosEstimation();
1369 
1370  COpenGLScene::Ptr scene = m_win->get3DSceneAndLock();
1371  COpenGLViewport::Ptr viewp = scene->getViewport("curr_robot_pose_viewport");
1372  viewp->getCamera().setPointingAt(CPose3D(curr_robot_pose));
1373 
1374  m_win->unlockAccess3DScene();
1375  m_win->forceRepaint();
1376  MRPT_LOG_DEBUG_STREAM("Updated the \"current_pos\" viewport");
1377 
1378  MRPT_END;
1379 }
1380 
1381 template <class GRAPH_T>
1383  const std::string& fname_GT, std::vector<mrpt::poses::CPose2D>* gt_poses,
1384  std::vector<mrpt::system::TTimeStamp>* gt_timestamps /* = NULL */)
1385 {
1386  MRPT_START;
1387  using namespace std;
1388  using namespace mrpt::system;
1389 
1390  // make sure file exists
1391  ASSERTDEBMSG_(
1392  fileExists(fname_GT),
1393  format(
1394  "\nGround-truth file %s was not found.\n"
1395  "Either specify a valid ground-truth filename or set set the "
1396  "m_visualize_GT flag to false\n",
1397  fname_GT.c_str()));
1398 
1399  mrpt::io::CFileInputStream file_GT(fname_GT);
1400  ASSERTDEBMSG_(file_GT.fileOpenCorrectly(), "\nCouldn't open GT file\n");
1401  ASSERTDEBMSG_(gt_poses, "\nNo valid std::vector<pose_t>* was given\n");
1402 
1403  string curr_line;
1404 
1405  // parse the file - get timestamp and pose and fill in the pose_t vector
1406  for (size_t line_num = 0; file_GT.readLine(curr_line); line_num++)
1407  {
1408  vector<string> curr_tokens;
1409  system::tokenize(curr_line, " ", curr_tokens);
1410 
1411  // check the current pose dimensions
1412  ASSERTDEBMSG_(
1413  curr_tokens.size() == constraint_t::state_length + 1,
1414  "\nGround Truth File doesn't seem to contain data as generated by "
1415  "the "
1416  "GridMapNavSimul application.\n Either specify the GT file format "
1417  "or set "
1418  "visualize_ground_truth to false in the .ini file\n");
1419 
1420  // timestamp
1421  if (gt_timestamps)
1422  {
1423  auto timestamp =
1424  mrpt::Clock::fromDouble(atof(curr_tokens[0].c_str()));
1425  gt_timestamps->push_back(timestamp);
1426  }
1427 
1428  // pose
1429  pose_t curr_pose(
1430  atof(curr_tokens[1].c_str()), atof(curr_tokens[2].c_str()),
1431  atof(curr_tokens[3].c_str()));
1432  gt_poses->push_back(curr_pose);
1433  }
1434 
1435  file_GT.close();
1436 
1437  MRPT_END;
1438 }
1439 template <class GRAPH_T>
1441  const std::string& fname_GT, std::vector<mrpt::poses::CPose3D>* gt_poses,
1442  std::vector<mrpt::system::TTimeStamp>* gt_timestamps /* = NULL */)
1443 {
1444  THROW_EXCEPTION("Not implemented.");
1445 }
1446 
1447 template <class GRAPH_T>
1449  const std::string& fname_GT, std::vector<mrpt::poses::CPose2D>* gt_poses,
1450  std::vector<mrpt::system::TTimeStamp>* gt_timestamps /*= NULL */)
1451 {
1452  MRPT_START;
1453  using namespace std;
1454  using namespace mrpt::math;
1455  using namespace mrpt::system;
1456 
1457  // make sure file exists
1458  ASSERTDEBMSG_(
1459  fileExists(fname_GT),
1460  format(
1461  "\nGround-truth file %s was not found.\n"
1462  "Either specify a valid ground-truth filename or set set the "
1463  "m_visualize_GT flag to false\n",
1464  fname_GT.c_str()));
1465 
1466  mrpt::io::CFileInputStream file_GT(fname_GT);
1467  ASSERTDEBMSG_(
1468  file_GT.fileOpenCorrectly(),
1469  "\nreadGTFileRGBD_TUM: Couldn't openGT file\n");
1470  ASSERTDEBMSG_(gt_poses, "No valid std::vector<pose_t>* was given");
1471 
1472  string curr_line;
1473 
1474  // move to the first non-commented immediately - comments before this..
1475  for (size_t i = 0; file_GT.readLine(curr_line); i++)
1476  {
1477  if (curr_line.at(0) != '#')
1478  {
1479  break;
1480  }
1481  }
1482 
1483  // handle the first pose seperately
1484  // make sure that the ground-truth starts at 0.
1485  pose_t pose_diff;
1486  vector<string> curr_tokens;
1487  mrpt::system::tokenize(curr_line, " ", curr_tokens);
1488 
1489  // check the current pose dimensions
1490  ASSERTDEBMSG_(
1491  curr_tokens.size() == 8,
1492  "\nGround Truth File doesn't seem to contain data as specified in "
1493  "RGBD_TUM related "
1494  "datasets.\n Either specify correct the GT file format or set "
1495  "visualize_ground_truth to false in the .ini file\n");
1496 
1497  // quaternion
1498  CQuaternionDouble quat;
1499  quat.r(atof(curr_tokens[7].c_str()));
1500  quat.x(atof(curr_tokens[4].c_str()));
1501  quat.y(atof(curr_tokens[5].c_str()));
1502  quat.z(atof(curr_tokens[6].c_str()));
1503  double r, p, y;
1504  quat.rpy(r, p, y);
1505 
1506  CVectorDouble curr_coords(3);
1507  curr_coords[0] = atof(curr_tokens[1].c_str());
1508  curr_coords[1] = atof(curr_tokens[2].c_str());
1509  curr_coords[2] = atof(curr_tokens[3].c_str());
1510 
1511  // initial pose
1512  pose_t curr_pose(curr_coords[0], curr_coords[1], y);
1513  // pose_t curr_pose(0, 0, 0);
1514 
1515  pose_diff = curr_pose;
1516 
1517  // parse the file - get timestamp and pose and fill in the pose_t vector
1518  for (; file_GT.readLine(curr_line);)
1519  {
1520  system::tokenize(curr_line, " ", curr_tokens);
1521  ASSERTDEBMSG_(
1522  curr_tokens.size() == 8,
1523  "\nGround Truth File doesn't seem to contain data as specified in "
1524  "RGBD_TUM related "
1525  "datasets.\n Either specify correct the GT file format or set "
1526  "visualize_ground_truth to false in the .ini file\n");
1527 
1528  // timestamp
1529  if (gt_timestamps)
1530  {
1531  auto timestamp =
1532  mrpt::Clock::fromDouble(atof(curr_tokens[0].c_str()));
1533  gt_timestamps->push_back(timestamp);
1534  }
1535 
1536  // quaternion
1537  quat.r(atof(curr_tokens[7].c_str()));
1538  quat.x(atof(curr_tokens[4].c_str()));
1539  quat.y(atof(curr_tokens[5].c_str()));
1540  quat.z(atof(curr_tokens[6].c_str()));
1541  quat.rpy(r, p, y);
1542 
1543  // pose
1544  curr_coords[0] = atof(curr_tokens[1].c_str());
1545  curr_coords[1] = atof(curr_tokens[2].c_str());
1546  curr_coords[2] = atof(curr_tokens[3].c_str());
1547 
1548  // current ground-truth pose
1549  pose_t p(curr_coords[0], curr_coords[1], y);
1550 
1551  p.x() -= pose_diff.x();
1552  p.y() -= pose_diff.y();
1553  p.phi() -= pose_diff.phi();
1554  // curr_pose += -pose_diff;
1555  gt_poses->push_back(p);
1556  }
1557 
1558  file_GT.close();
1559 
1560  MRPT_END;
1561 }
1562 
1563 template <class GRAPH_T>
1565 {
1566  MRPT_START;
1567  using namespace std;
1568  using namespace mrpt::math;
1569 
1570  // aligning GT (optical) frame with the MRPT frame
1571  // Set the rotation matrix from the corresponding RPY angles
1572  // MRPT Frame: X->forward; Y->Left; Z->Upward
1573  // Optical Frame: X->Right; Y->Downward; Z->Forward
1574  ASSERTDEB_(m_has_read_config);
1575  // rotz
1576  double anglez = DEG2RAD(0.0);
1577  const double tmpz[] = {
1578  cos(anglez), -sin(anglez), 0, sin(anglez), cos(anglez), 0, 0, 0, 1};
1579  CMatrixDouble rotz(3, 3, tmpz);
1580 
1581  // roty
1582  double angley = DEG2RAD(0.0);
1583  // double angley = DEG2RAD(90.0);
1584  const double tmpy[] = {cos(angley), 0, sin(angley), 0, 1, 0,
1585  -sin(angley), 0, cos(angley)};
1586  CMatrixDouble roty(3, 3, tmpy);
1587 
1588  // rotx
1589  // double anglex = DEG2RAD(-90.0);
1590  double anglex = DEG2RAD(0.0);
1591  const double tmpx[] = {
1592  1, 0, 0, 0, cos(anglex), -sin(anglex), 0, sin(anglex), cos(anglex)};
1593  CMatrixDouble rotx(3, 3, tmpx);
1594 
1595  stringstream ss_out;
1596  ss_out << "\nConstructing the rotation matrix for the GroundTruth Data..."
1597  << endl;
1598  m_rot_TUM_to_MRPT = rotz * roty * rotx;
1599 
1600  ss_out << "Rotation matrices for optical=>MRPT transformation" << endl;
1601  ss_out << "rotz: " << endl << rotz << endl;
1602  ss_out << "roty: " << endl << roty << endl;
1603  ss_out << "rotx: " << endl << rotx << endl;
1604  ss_out << "Full rotation matrix: " << endl << m_rot_TUM_to_MRPT << endl;
1605 
1606  MRPT_LOG_DEBUG_STREAM(ss_out);
1607 
1608  MRPT_END;
1609 }
1610 
1611 template <class GRAPH_T>
1613 {
1614  MRPT_START;
1615  ASSERTDEB_(m_enable_visuals);
1616  ASSERTDEBMSG_(
1617  m_win_observer,
1618  "\nqueryObserverForEvents method was called even though no Observer "
1619  "object was provided\n");
1620 
1621  std::map<std::string, bool> events_occurred;
1622  m_win_observer->returnEventsStruct(&events_occurred);
1623  m_request_to_exit = events_occurred.find("Ctrl+c")->second;
1624 
1625  // odometry visualization
1626  if (events_occurred[m_keystroke_odometry])
1627  {
1628  this->toggleOdometryVisualization();
1629  }
1630  // GT visualization
1631  if (events_occurred[m_keystroke_GT])
1632  {
1633  this->toggleGTVisualization();
1634  }
1635  // Map visualization
1636  if (events_occurred[m_keystroke_map])
1637  {
1638  this->toggleMapVisualization();
1639  }
1640  // Estimated Trajectory Visualization
1641  if (events_occurred[m_keystroke_estimated_trajectory])
1642  {
1643  this->toggleEstimatedTrajectoryVisualization();
1644  }
1645  // pause/resume program execution
1646  if (events_occurred[m_keystroke_pause_exec])
1647  {
1648  this->togglePause();
1649  }
1650 
1651  // notify the deciders/optimizer of any events they may be interested in
1652  // MRPT_LOG_DEBUG_STREAM("Notifying deciders/optimizer for events");
1653  m_node_reg->notifyOfWindowEvents(events_occurred);
1654  m_edge_reg->notifyOfWindowEvents(events_occurred);
1655  m_optimizer->notifyOfWindowEvents(events_occurred);
1656 
1657  MRPT_END;
1658 }
1659 
1660 template <class GRAPH_T>
1662 {
1663  MRPT_START;
1664  ASSERTDEB_(m_enable_visuals);
1665  using namespace mrpt::opengl;
1666  MRPT_LOG_INFO_STREAM("Toggling Odometry visualization...");
1667 
1668  COpenGLScene::Ptr scene = m_win->get3DSceneAndLock();
1669 
1670  if (m_visualize_odometry_poses)
1671  {
1672  CRenderizable::Ptr obj = scene->getByName("odometry_poses_cloud");
1673  obj->setVisibility(!obj->isVisible());
1674 
1675  obj = scene->getByName("robot_odometry_poses");
1676  obj->setVisibility(!obj->isVisible());
1677  }
1678  else
1679  {
1680  dumpVisibilityErrorMsg("visualize_odometry_poses");
1681  }
1682 
1683  m_win->unlockAccess3DScene();
1684  m_win->forceRepaint();
1685 
1686  MRPT_END;
1687 }
1688 template <class GRAPH_T>
1690 {
1691  MRPT_START;
1692  ASSERTDEB_(m_enable_visuals);
1693  using namespace mrpt::opengl;
1694  MRPT_LOG_INFO_STREAM("Toggling Ground Truth visualization");
1695 
1696  COpenGLScene::Ptr scene = m_win->get3DSceneAndLock();
1697 
1698  if (m_visualize_GT)
1699  {
1700  CRenderizable::Ptr obj = scene->getByName("GT_cloud");
1701  obj->setVisibility(!obj->isVisible());
1702 
1703  obj = scene->getByName("robot_GT");
1704  obj->setVisibility(!obj->isVisible());
1705  }
1706  else
1707  {
1708  dumpVisibilityErrorMsg("visualize_ground_truth");
1709  }
1710 
1711  m_win->unlockAccess3DScene();
1712  m_win->forceRepaint();
1713 
1714  MRPT_END;
1715 }
1716 template <class GRAPH_T>
1718 {
1719  MRPT_START;
1720  ASSERTDEB_(m_enable_visuals);
1721  using namespace std;
1722  using namespace mrpt::opengl;
1723  MRPT_LOG_INFO_STREAM("Toggling Map visualization... ");
1724 
1725  COpenGLScene::Ptr scene = m_win->get3DSceneAndLock();
1726 
1727  // get total number of nodes
1728  int num_of_nodes;
1729  {
1730  std::lock_guard<std::mutex> graph_lock(m_graph_section);
1731  num_of_nodes = m_graph.nodeCount();
1732  }
1733 
1734  // name of gui object
1735  stringstream scan_name("");
1736 
1737  for (int node_cnt = 0; node_cnt != num_of_nodes; ++node_cnt)
1738  {
1739  // build the name of the potential corresponding object in the scene
1740  scan_name.str("");
1741  scan_name << "laser_scan_";
1742  scan_name << node_cnt;
1743 
1744  CRenderizable::Ptr obj = scene->getByName(scan_name.str());
1745  // current node may not have laserScans => may not have corresponding
1746  // obj
1747  if (obj)
1748  {
1749  obj->setVisibility(!obj->isVisible());
1750  }
1751  }
1752  m_win->unlockAccess3DScene();
1753  m_win->forceRepaint();
1754 
1755  MRPT_END;
1756 }
1757 template <class GRAPH_T>
1759 {
1760  MRPT_START;
1761  ASSERTDEB_(m_enable_visuals);
1762  using namespace mrpt::opengl;
1763  MRPT_LOG_INFO_STREAM("Toggling Estimated Trajectory visualization... ");
1764 
1765  COpenGLScene::Ptr scene = m_win->get3DSceneAndLock();
1766 
1767  if (m_visualize_estimated_trajectory)
1768  {
1769  CRenderizable::Ptr obj = scene->getByName("estimated_traj_setoflines");
1770  obj->setVisibility(!obj->isVisible());
1771 
1772  obj = scene->getByName("robot_estimated_traj");
1773  obj->setVisibility(!obj->isVisible());
1774  }
1775  else
1776  {
1777  dumpVisibilityErrorMsg("visualize_estimated_trajectory");
1778  }
1779 
1780  m_win->unlockAccess3DScene();
1781  m_win->forceRepaint();
1782 
1783  MRPT_END;
1784 }
1785 template <class GRAPH_T>
1787  std::string viz_flag, int sleep_time /* = 500 milliseconds */)
1788 {
1789  MRPT_START;
1790 
1792  "Cannot toggle visibility of specified object.\n"
1793  << "Make sure that the corresponding visualization flag (" << viz_flag
1794  << ") is set to true in the .ini file.");
1795  std::this_thread::sleep_for(std::chrono::milliseconds(sleep_time));
1796 
1797  MRPT_END;
1798 }
1799 
1800 template <class GRAPH_T>
1802  const mrpt::obs::CActionCollection::Ptr action,
1803  const mrpt::obs::CSensoryFrame::Ptr observations,
1804  const mrpt::obs::CObservation::Ptr observation)
1805 {
1806  MRPT_START;
1807  using namespace mrpt::obs;
1808  using namespace mrpt::system;
1809 
1810  // make sure that adequate data is given.
1811  ASSERTDEBMSG_(
1812  action || observation,
1813  "Neither action or observation contains valid data.");
1814 
1816  if (observation)
1817  {
1818  timestamp = observation->timestamp;
1819  }
1820  else
1821  {
1822  // querry action part first
1823  timestamp = action->get(0)->timestamp;
1824 
1825  // if still not available query the observations in the CSensoryFrame
1826  if (timestamp == INVALID_TIMESTAMP)
1827  {
1829  observations->begin();
1830  sens_it != observations->end(); ++sens_it)
1831  {
1832  timestamp = (*sens_it)->timestamp;
1833  if (timestamp != INVALID_TIMESTAMP)
1834  {
1835  break;
1836  }
1837  }
1838  }
1839  }
1840  return timestamp;
1841  MRPT_END;
1842 }
1843 
1844 template <class GRAPH_T>
1847  const mrpt::graphs::TNodeID nodeID) const
1848 {
1849  return mrpt::poses::CPose3D(m_graph.nodes.at(nodeID));
1850 }
1851 
1852 template <class GRAPH_T>
1854 {
1855  using namespace mrpt::opengl;
1856 
1857  CSetOfObjects::Ptr map_obj = mrpt::make_aligned_shared<CSetOfObjects>();
1858  map_obj->setName("map");
1859  COpenGLScene::Ptr& scene = this->m_win->get3DSceneAndLock();
1860  scene->insert(map_obj);
1861  this->m_win->unlockAccess3DScene();
1862  this->m_win->forceRepaint();
1863 }
1864 
1865 template <class GRAPH_T>
1867  const std::map<
1869  nodes_to_laser_scans2D,
1870  bool full_update /*= false */)
1871 {
1872  MRPT_START;
1873  ASSERTDEB_(m_enable_visuals);
1874  using namespace mrpt::obs;
1875  using namespace mrpt::opengl;
1876  using namespace std;
1877  using namespace mrpt::poses;
1878  COpenGLScene::Ptr scene = m_win->get3DSceneAndLock();
1879  CSetOfObjects::Ptr map_obj;
1880  {
1881  CRenderizable::Ptr obj = scene->getByName("map");
1882  map_obj = std::dynamic_pointer_cast<CSetOfObjects>(obj);
1883  ASSERTDEB_(map_obj);
1884  }
1885 
1886  mrpt::system::CTicTac map_update_timer;
1887  map_update_timer.Tic();
1888 
1889  // get the set of nodes for which to run the update
1890  std::set<mrpt::graphs::TNodeID> nodes_set;
1891  {
1892  if (full_update)
1893  {
1894  // for all the nodes get the node position and the corresponding
1895  // laser scan
1896  // if they were recorded and visualize them
1897  m_graph.getAllNodes(nodes_set);
1898  MRPT_LOG_DEBUG_STREAM("Executing full update of the map visuals");
1899  map_obj->clear();
1900 
1901  } // end if - full update
1902  else
1903  { // add only current nodeID
1904  nodes_set.insert(m_nodeID_max);
1905  } // end if - partial update
1906  }
1907 
1908  // for all the nodes in the previously populated set
1910  nodes_set.begin();
1911  node_it != nodes_set.end(); ++node_it)
1912  {
1913  // name of gui object
1914  stringstream scan_name("");
1915  scan_name << "laser_scan_";
1916  scan_name << *node_it;
1917 
1918  // get the node laser scan
1919  CObservation2DRangeScan::Ptr scan_content;
1920  std::map<
1923  nodes_to_laser_scans2D.find(*node_it);
1924 
1925  // make sure that the laser scan exists and is valid
1926  if (search != nodes_to_laser_scans2D.end() && search->second)
1927  {
1928  scan_content = search->second;
1929 
1930  CObservation2DRangeScan scan_decimated;
1931  this->decimateLaserScan(
1932  *scan_content, &scan_decimated,
1933  /*keep_every_n_entries = */ 5);
1934 
1935  // if the scan doesn't already exist, add it to the map object,
1936  // otherwise just
1937  // adjust its pose
1938  CRenderizable::Ptr obj = map_obj->getByName(scan_name.str());
1939  CSetOfObjects::Ptr scan_obj =
1940  std::dynamic_pointer_cast<CSetOfObjects>(obj);
1941  if (!scan_obj)
1942  {
1943  scan_obj = mrpt::make_aligned_shared<CSetOfObjects>();
1944 
1945  // creating and inserting the observation in the CSetOfObjects
1947  m.insertObservation(&scan_decimated);
1948  m.getAs3DObject(scan_obj);
1949 
1950  scan_obj->setName(scan_name.str());
1951  this->setObjectPropsFromNodeID(*node_it, scan_obj);
1952 
1953  // set the visibility of the object the same value as the
1954  // visibility of
1955  // the previous - Needed for proper toggling of the visibility
1956  // of the
1957  // whole map
1958  {
1959  stringstream prev_scan_name("");
1960  prev_scan_name << "laser_scan_" << *node_it - 1;
1961  CRenderizable::Ptr prev_obj =
1962  map_obj->getByName(prev_scan_name.str());
1963  if (prev_obj)
1964  {
1965  scan_obj->setVisibility(prev_obj->isVisible());
1966  }
1967  }
1968 
1969  map_obj->insert(scan_obj);
1970  }
1971  else
1972  {
1973  scan_obj = std::dynamic_pointer_cast<CSetOfObjects>(scan_obj);
1974  }
1975 
1976  // finally set the pose correctly - as computed by graphSLAM
1977  const CPose3D& scan_pose = CPose3D(m_graph.nodes.at(*node_it));
1978  scan_obj->setPose(scan_pose);
1979  }
1980  else
1981  {
1983  "Laser scans of NodeID " << *node_it << "are empty/invalid");
1984  }
1985 
1986  } // end for set of nodes
1987 
1988  m_win->unlockAccess3DScene();
1989  m_win->forceRepaint();
1990 
1991  double elapsed_time = map_update_timer.Tac();
1993  "updateMapVisualization took: " << elapsed_time << "s");
1994  MRPT_END;
1995 } // end of updateMapVisualization
1996 
1997 template <class GRAPH_T>
1999  const mrpt::graphs::TNodeID nodeID,
2001 {
2002  MRPT_START;
2003  viz_object->setColor_u8(m_optimized_map_color);
2004  MRPT_END;
2005 }
2006 
2007 template <class GRAPH_T>
2009  mrpt::obs::CObservation2DRangeScan& laser_scan_in,
2010  mrpt::obs::CObservation2DRangeScan* laser_scan_out,
2011  const int keep_every_n_entries /*= 2*/)
2012 {
2013  MRPT_START;
2014 
2015  size_t scan_size = laser_scan_in.scan.size();
2016 
2017  // assign the decimated scans, ranges
2018  std::vector<float> new_scan(
2019  scan_size); // Was [], but can't use non-constant argument with arrays
2020  std::vector<char> new_validRange(scan_size);
2021  size_t new_scan_size = 0;
2022  for (size_t i = 0; i != scan_size; i++)
2023  {
2024  if (i % keep_every_n_entries == 0)
2025  {
2026  new_scan[new_scan_size] = laser_scan_in.scan[i];
2027  new_validRange[new_scan_size] = laser_scan_in.validRange[i];
2028  new_scan_size++;
2029  }
2030  }
2031  laser_scan_out->loadFromVectors(
2032  new_scan_size, &new_scan[0], &new_validRange[0]);
2033 
2034  MRPT_END;
2035 }
2036 
2037 template <class GRAPH_T>
2039 {
2040  MRPT_START;
2041  ASSERTDEB_(m_enable_visuals);
2042  using namespace mrpt::opengl;
2043 
2044  // assertions
2045  ASSERTDEB_(m_has_read_config);
2046  ASSERTDEB_(
2047  m_win &&
2048  "Visualization of data was requested but no CDisplayWindow3D pointer "
2049  "was provided");
2050 
2051  // point cloud
2052  CPointCloud::Ptr GT_cloud = mrpt::make_aligned_shared<CPointCloud>();
2053  GT_cloud->setPointSize(1.0);
2054  GT_cloud->enablePointSmooth();
2055  GT_cloud->enableColorFromX(false);
2056  GT_cloud->enableColorFromY(false);
2057  GT_cloud->enableColorFromZ(false);
2058  GT_cloud->setColor_u8(m_GT_color);
2059  GT_cloud->setName("GT_cloud");
2060 
2061  // robot model
2062  CSetOfObjects::Ptr robot_model = this->setCurrentPositionModel(
2063  /*name = */ "robot_GT",
2064  /*color = */ m_GT_color,
2065  /*scale = */ m_robot_model_size);
2066 
2067  // insert them to the scene
2068  COpenGLScene::Ptr scene = m_win->get3DSceneAndLock();
2069  scene->insert(GT_cloud);
2070  scene->insert(robot_model);
2071  m_win->unlockAccess3DScene();
2072 
2073  m_win_manager->assignTextMessageParameters(
2074  /* offset_y* = */ &m_offset_y_GT,
2075  /* text_index* = */ &m_text_index_GT);
2076  m_win_manager->addTextMessage(
2077  m_offset_x_left, -m_offset_y_GT, mrpt::format("Ground truth path"),
2078  mrpt::img::TColorf(m_GT_color),
2079  /* unique_index = */ m_text_index_GT);
2080 
2081  m_win->forceRepaint();
2082 
2083  MRPT_END;
2084 } // end of initGTVisualization
2085 
2086 template <class GRAPH_T>
2088 {
2089  MRPT_START;
2090  ASSERTDEB_(m_enable_visuals);
2091  using namespace mrpt::opengl;
2092 
2093  // add to the GT PointCloud and visualize it
2094  // check that GT vector is not depleted
2095  if (m_visualize_GT && m_GT_poses_index < m_GT_poses.size())
2096  {
2097  ASSERTDEB_(
2098  m_win &&
2099  "Visualization of data was requested but no CDisplayWindow3D "
2100  "pointer was given");
2101 
2102  COpenGLScene::Ptr scene = m_win->get3DSceneAndLock();
2103 
2104  CRenderizable::Ptr obj = scene->getByName("GT_cloud");
2105  CPointCloud::Ptr GT_cloud = std::dynamic_pointer_cast<CPointCloud>(obj);
2106 
2107  // add the latest GT pose
2108  mrpt::poses::CPose3D p(m_GT_poses[m_GT_poses_index]);
2109  GT_cloud->insertPoint(p.x(), p.y(), p.z());
2110 
2111  // robot model of GT trajectory
2112  obj = scene->getByName("robot_GT");
2113  CSetOfObjects::Ptr robot_obj =
2114  std::dynamic_pointer_cast<CSetOfObjects>(obj);
2115  robot_obj->setPose(p);
2116  m_win->unlockAccess3DScene();
2117  m_win->forceRepaint();
2118  }
2119 
2120  MRPT_END;
2121 } // end of updateGTVisualization
2122 
2123 template <class GRAPH_T>
2125 {
2126  MRPT_START;
2127  ASSERTDEB_(m_has_read_config);
2128  ASSERTDEB_(m_enable_visuals);
2129  using namespace mrpt::opengl;
2130 
2131  // point cloud
2132  CPointCloud::Ptr odometry_poses_cloud =
2133  mrpt::make_aligned_shared<CPointCloud>();
2134  odometry_poses_cloud->setPointSize(1.0);
2135  odometry_poses_cloud->enablePointSmooth();
2136  odometry_poses_cloud->enableColorFromX(false);
2137  odometry_poses_cloud->enableColorFromY(false);
2138  odometry_poses_cloud->enableColorFromZ(false);
2139  odometry_poses_cloud->setColor_u8(m_odometry_color);
2140  odometry_poses_cloud->setName("odometry_poses_cloud");
2141 
2142  // robot model
2143  CSetOfObjects::Ptr robot_model = this->setCurrentPositionModel(
2144  "robot_odometry_poses", m_odometry_color, m_robot_model_size);
2145 
2146  // insert them to the scene
2147  COpenGLScene::Ptr scene = m_win->get3DSceneAndLock();
2148  scene->insert(odometry_poses_cloud);
2149  scene->insert(robot_model);
2150  m_win->unlockAccess3DScene();
2151 
2152  m_win_manager->assignTextMessageParameters(
2153  /* offset_y* = */ &m_offset_y_odometry,
2154  /* text_index* = */ &m_text_index_odometry);
2155  m_win_manager->addTextMessage(
2156  m_offset_x_left, -m_offset_y_odometry, mrpt::format("Odometry path"),
2157  mrpt::img::TColorf(m_odometry_color),
2158  /* unique_index = */ m_text_index_odometry);
2159 
2160  m_win->forceRepaint();
2161 
2162  MRPT_END;
2163 }
2164 
2165 template <class GRAPH_T>
2167 {
2168  MRPT_START;
2169  ASSERTDEB_(m_enable_visuals);
2170  ASSERTDEBMSG_(
2171  m_win,
2172  "Visualization of data was requested but no CDisplayWindow3D pointer "
2173  "was given");
2174  using namespace mrpt::opengl;
2175 
2176  COpenGLScene::Ptr scene = m_win->get3DSceneAndLock();
2177 
2178  // point cloud
2179  CRenderizable::Ptr obj = scene->getByName("odometry_poses_cloud");
2180  CPointCloud::Ptr odometry_poses_cloud =
2181  std::dynamic_pointer_cast<CPointCloud>(obj);
2182  mrpt::poses::CPose3D p(m_odometry_poses.back());
2183 
2184  odometry_poses_cloud->insertPoint(p.x(), p.y(), p.z());
2185 
2186  // robot model
2187  obj = scene->getByName("robot_odometry_poses");
2188  CSetOfObjects::Ptr robot_obj =
2189  std::dynamic_pointer_cast<CSetOfObjects>(obj);
2190  robot_obj->setPose(p);
2191 
2192  m_win->unlockAccess3DScene();
2193  m_win->forceRepaint();
2194 
2195  MRPT_END;
2196 }
2197 
2198 template <class GRAPH_T>
2200 {
2201  MRPT_START;
2202  ASSERTDEB_(m_enable_visuals);
2203  using namespace mrpt::opengl;
2204 
2205  // SetOfLines
2206  CSetOfLines::Ptr estimated_traj_setoflines =
2207  mrpt::make_aligned_shared<CSetOfLines>();
2208  estimated_traj_setoflines->setColor_u8(m_estimated_traj_color);
2209  estimated_traj_setoflines->setLineWidth(1.5);
2210  estimated_traj_setoflines->setName("estimated_traj_setoflines");
2211  // append a dummy line so that you can later use append using
2212  // CSetOfLines::appendLienStrip method.
2213  estimated_traj_setoflines->appendLine(
2214  /* 1st */ 0, 0, 0,
2215  /* 2nd */ 0, 0, 0);
2216 
2217  // robot model
2218  // pose_t initial_pose;
2219  CSetOfObjects::Ptr robot_model = this->setCurrentPositionModel(
2220  "robot_estimated_traj", m_estimated_traj_color, m_robot_model_size);
2221 
2222  // insert objects in the graph
2223  COpenGLScene::Ptr scene = m_win->get3DSceneAndLock();
2224  if (m_visualize_estimated_trajectory)
2225  {
2226  scene->insert(estimated_traj_setoflines);
2227  }
2228  scene->insert(robot_model);
2229  m_win->unlockAccess3DScene();
2230 
2231  if (m_visualize_estimated_trajectory)
2232  {
2233  m_win_manager->assignTextMessageParameters(
2234  /* offset_y* = */ &m_offset_y_estimated_traj,
2235  /* text_index* = */ &m_text_index_estimated_traj);
2236  m_win_manager->addTextMessage(
2237  m_offset_x_left, -m_offset_y_estimated_traj,
2238  mrpt::format("Estimated trajectory"),
2239  mrpt::img::TColorf(m_estimated_traj_color),
2240  /* unique_index = */ m_text_index_estimated_traj);
2241  }
2242 
2243  m_win->forceRepaint();
2244 
2245  MRPT_END;
2246 }
2247 
2248 template <class GRAPH_T>
2250  bool full_update)
2251 {
2252  MRPT_START;
2253  ASSERTDEB_(m_enable_visuals);
2254  using namespace mrpt::opengl;
2255 
2256  std::lock_guard<std::mutex> graph_lock(m_graph_section);
2257  ASSERTDEB_(m_graph.nodeCount() != 0);
2258 
2259  COpenGLScene::Ptr scene = m_win->get3DSceneAndLock();
2260 
2262  if (m_visualize_estimated_trajectory)
2263  {
2264  // set of lines
2265  obj = scene->getByName("estimated_traj_setoflines");
2266  CSetOfLines::Ptr estimated_traj_setoflines =
2267  std::dynamic_pointer_cast<CSetOfLines>(obj);
2268 
2269  // gather set of nodes for which to append lines - all of the nodes in
2270  // the graph or just the last inserted..
2271  std::set<mrpt::graphs::TNodeID> nodes_set;
2272  {
2273  if (full_update)
2274  {
2275  this->getNodeIDsOfEstimatedTrajectory(&nodes_set);
2276  estimated_traj_setoflines->clear();
2277  // dummy way so that I can use appendLineStrip afterwards.
2278  estimated_traj_setoflines->appendLine(
2279  /* 1st */ 0, 0, 0,
2280  /* 2nd */ 0, 0, 0);
2281  }
2282  else
2283  {
2284  nodes_set.insert(m_graph.nodeCount() - 1);
2285  }
2286  }
2287  // append line for each node in the set
2289  nodes_set.begin();
2290  it != nodes_set.end(); ++it)
2291  {
2292  mrpt::poses::CPose3D p(m_graph.nodes.at(*it));
2293 
2294  estimated_traj_setoflines->appendLineStrip(p.x(), p.y(), p.z());
2295  }
2296  }
2297 
2298  // robot model
2299  // set the robot position to the last recorded pose in the graph
2300  obj = scene->getByName("robot_estimated_traj");
2301  CSetOfObjects::Ptr robot_obj =
2302  std::dynamic_pointer_cast<CSetOfObjects>(obj);
2303  pose_t curr_estimated_pos = m_graph.nodes[m_graph.nodeCount() - 1];
2304  robot_obj->setPose(curr_estimated_pos);
2305 
2306  m_win->unlockAccess3DScene();
2307  m_win->forceRepaint();
2308  MRPT_END;
2309 } // end of updateEstimatedTrajectoryVisualization
2310 
2311 // TRGBDInfoFileParams
2312 // ////////////////////////////////
2313 template <class GRAPH_T>
2315  const std::string& rawlog_fname)
2316 {
2317  this->setRawlogFile(rawlog_fname);
2318  this->initTRGBDInfoFileParams();
2319 }
2320 template <class GRAPH_T>
2322 {
2323  this->initTRGBDInfoFileParams();
2324 }
2325 template <class GRAPH_T>
2327 {
2328 }
2329 
2330 template <class GRAPH_T>
2332  const std::string& rawlog_fname)
2333 {
2334  // get the correct info filename from the rawlog_fname
2336  std::string rawlog_filename = mrpt::system::extractFileName(rawlog_fname);
2337  std::string name_prefix = "rawlog_";
2338  std::string name_suffix = "_info.txt";
2339  info_fname = dir + name_prefix + rawlog_filename + name_suffix;
2340 }
2341 
2342 template <class GRAPH_T>
2344 {
2345  // fields to use
2346  fields["Overall number of objects"] = "";
2347  fields["Observations format"] = "";
2348 }
2349 
2350 template <class GRAPH_T>
2352 {
2353  ASSERT_FILE_EXISTS_(info_fname);
2354  using namespace std;
2355 
2356  // open file
2357  mrpt::io::CFileInputStream info_file(info_fname);
2358  ASSERTDEBMSG_(
2359  info_file.fileOpenCorrectly(),
2360  "\nTRGBDInfoFileParams::parseFile: Couldn't open info file\n");
2361 
2362  string curr_line;
2363  size_t line_cnt = 0;
2364 
2365  // parse until you find an empty line.
2366  while (true)
2367  {
2368  info_file.readLine(curr_line);
2369  line_cnt++;
2370  if (curr_line.size() == 0) break;
2371  }
2372 
2373  // parse the meaningful data
2374  while (info_file.readLine(curr_line))
2375  {
2376  // split current line at ":"
2377  vector<string> curr_tokens;
2378  mrpt::system::tokenize(curr_line, ":", curr_tokens);
2379 
2380  ASSERTDEB_EQUAL_(curr_tokens.size(), 2);
2381 
2382  // evaluate the name. if name in info struct then fill the corresponding
2383  // info struct parameter with the value_part in the file.
2384  std::string literal_part = mrpt::system::trim(curr_tokens[0]);
2385  std::string value_part = mrpt::system::trim(curr_tokens[1]);
2386 
2387  for (std::map<std::string, std::string>::iterator it = fields.begin();
2388  it != fields.end(); ++it)
2389  {
2390  if (mrpt::system::strCmpI(it->first, literal_part))
2391  {
2392  it->second = value_part;
2393  }
2394  }
2395 
2396  line_cnt++;
2397  }
2398 }
2399 ////////////////////////////////////////////////////////////////////////////////
2400 
2401 template <class GRAPH_T>
2403  const std::string* fname_in /*= NULL */) const
2404 {
2405  MRPT_START;
2406 
2407  // what's the name of the file to be saved?
2408  std::string fname;
2409  if (fname_in)
2410  {
2411  fname = *fname_in;
2412  }
2413  else
2414  {
2415  fname = "output_graph.graph";
2416  }
2417 
2419  "Saving generated graph in VERTEX/EDGE format: " << fname);
2420  m_graph.saveToTextFile(fname);
2421 
2422  MRPT_END;
2423 }
2424 
2425 template <class GRAPH_T>
2427  const std::string* fname_in /* = NULL */) const
2428 {
2429  MRPT_START;
2430  ASSERTDEBMSG_(
2431  m_enable_visuals,
2432  "\nsave3DScene was called even though enable_visuals flag is "
2433  "off.\nExiting...\n");
2434  using namespace mrpt::opengl;
2435 
2436  COpenGLScene::Ptr scene = m_win->get3DSceneAndLock();
2437 
2438  if (!scene)
2439  {
2441  "Could not fetch 3D Scene. Display window must already be closed.");
2442  return;
2443  }
2444 
2445  // TODO - what else is there to be excluded from the scene?
2446  // remove the CPlanarLaserScan if it exists
2447  {
2448  CPlanarLaserScan::Ptr laser_scan;
2449  for (; (laser_scan = scene->getByClass<CPlanarLaserScan>());)
2450  {
2452  "Removing CPlanarLaserScan from generated 3DScene...");
2453  scene->removeObject(laser_scan);
2454  }
2455  }
2456 
2457  // what's the name of the file to be saved?
2458  std::string fname;
2459  if (fname_in)
2460  {
2461  fname = *fname_in;
2462  }
2463  else
2464  {
2465  fname = "output_scene.3DScene";
2466  }
2467 
2468  MRPT_LOG_INFO_STREAM("Saving generated scene to " << fname);
2469  scene->saveToFile(fname);
2470 
2471  m_win->unlockAccess3DScene();
2472  m_win->forceRepaint();
2473 
2474  MRPT_END;
2475 }
2476 
2477 template <class GRAPH_T>
2479  mrpt::graphs::TNodeID nodeID, size_t gt_index)
2480 {
2481  MRPT_START;
2482  using namespace mrpt::math;
2483  using namespace mrpt::poses;
2484 
2485  // start updating the metric after a certain number of nodes have been added
2486  if (m_graph.nodeCount() < 4)
2487  {
2488  return;
2489  }
2490 
2491  // add to the map - keep track of which gt index corresponds to which nodeID
2492  m_nodeID_to_gt_indices[nodeID] = gt_index;
2493 
2494  // initialize the loop variables only once
2495  pose_t curr_node_pos;
2496  pose_t curr_gt_pos;
2497  pose_t node_delta_pos;
2498  pose_t gt_delta;
2499  double trans_diff = 0;
2500  double rot_diff = 0;
2501 
2502  size_t indices_size = m_nodeID_to_gt_indices.size();
2503 
2504  // recompute the metric from scratch
2505  m_curr_deformation_energy = 0;
2506 
2507  // first element of map
2508  // std::map<mrpt::graphs::TNodeID, size_t>::const_iterator start_it =
2509  // std::next(m_nodeID_to_gt_indices.begin(), 1);
2511  m_nodeID_to_gt_indices.begin();
2512  start_it++;
2513 
2514  // fetch the first node, gt positions separately
2515  // std::map<mrpt::graphs::TNodeID, size_t>::const_iterator prev_it =
2516  // std::prev(start_it, 1);
2518  prev_it--;
2519  pose_t prev_node_pos = m_graph.nodes[prev_it->first];
2520  pose_t prev_gt_pos = m_GT_poses[prev_it->second];
2521 
2522  // temporary constraint type
2523  constraint_t c;
2524 
2526  start_it;
2527  index_it != m_nodeID_to_gt_indices.end(); index_it++)
2528  {
2529  curr_node_pos = m_graph.nodes[index_it->first];
2530  curr_gt_pos = m_GT_poses[index_it->second];
2531 
2532  node_delta_pos = curr_node_pos - prev_node_pos;
2533  gt_delta = curr_gt_pos - prev_gt_pos;
2534 
2535  trans_diff = gt_delta.distanceTo(node_delta_pos);
2536  rot_diff = this->accumulateAngleDiffs(gt_delta, node_delta_pos);
2537 
2538  m_curr_deformation_energy += (pow(trans_diff, 2) + pow(rot_diff, 2));
2539  m_curr_deformation_energy /= indices_size;
2540 
2541  // add it to the overall vector
2542  m_deformation_energy_vec.push_back(m_curr_deformation_energy);
2543 
2544  prev_node_pos = curr_node_pos;
2545  prev_gt_pos = curr_gt_pos;
2546  }
2547 
2549  "Total deformation energy: " << m_curr_deformation_energy);
2550 
2551  MRPT_END;
2552 }
2553 
2554 template <class GRAPH_T>
2556  const mrpt::poses::CPose2D& p1, const mrpt::poses::CPose2D& p2)
2557 {
2558  return mrpt::math::wrapToPi(p1.phi() - p2.phi());
2559 }
2560 template <class GRAPH_T>
2562  const mrpt::poses::CPose3D& p1, const mrpt::poses::CPose3D& p2)
2563 {
2564  using namespace mrpt::math;
2565  double res = 0;
2566 
2567  res += wrapToPi(p1.roll() - p2.roll());
2568  res += wrapToPi(p1.pitch() - p2.pitch());
2569  res += wrapToPi(p1.yaw() - p2.yaw());
2570 
2571  return res;
2572 }
2573 
2574 template <class GRAPH_T>
2576 {
2577  ASSERTDEB_(m_enable_visuals);
2578  using namespace std;
2579  using namespace mrpt::gui;
2580 
2581  MRPT_START;
2582  MRPT_LOG_DEBUG_STREAM("In initializeSlamMetricVisualization...");
2583  ASSERTDEB_(m_visualize_SLAM_metric);
2584 
2585  // initialize the m_win_plot on the stack
2586  m_win_plot = new CDisplayWindowPlots(
2587  "Evolution of SLAM metric - Deformation Energy (1:1000)", 400, 300);
2588 
2589  m_win_plot->setPos(20, 50);
2590  m_win_plot->clf();
2591  // just plot the deformation points from scratch every time
2592  m_win_plot->hold_off();
2593  m_win_plot->enableMousePanZoom(true);
2594 
2595  MRPT_END;
2596 }
2597 
2598 template <class GRAPH_T>
2600 {
2601  MRPT_START;
2602  ASSERTDEB_(m_enable_visuals);
2603  ASSERTDEB_(m_win_plot && m_visualize_SLAM_metric);
2604 
2605  // build the X, Y vectors for plotting - use log scale
2606  std::vector<double> x(m_deformation_energy_vec.size(), 0);
2607  std::vector<double> y(m_deformation_energy_vec.size(), 0);
2608  for (size_t i = 0; i != x.size(); i++)
2609  {
2610  x[i] = i;
2611  y[i] = m_deformation_energy_vec[i] * 1000;
2612  }
2613 
2614  m_win_plot->plot(
2615  x, y, "r-1",
2616  /*plotName = */ "Deformation Energy (x1000)");
2617 
2618  // set the limits so that he y-values can be monitored
2619  // set the xmin limit with respect to xmax, which is constantly growing
2621  xmax = std::max_element(x.begin(), x.end());
2622  ymax = std::max_element(y.begin(), y.end());
2623 
2624  m_win_plot->axis(
2625  /*x_min = */ xmax != x.end() ? -(*xmax / 12) : -1,
2626  /*x_max = */ (xmax != x.end() ? *xmax : 1),
2627  /*y_min = */ -0.4f,
2628  /*y_max = */ (ymax != y.end() ? *ymax : 1));
2629 
2630  MRPT_END;
2631 }
2632 
2633 template <class GRAPH_T>
2635  std::string* report_str) const
2636 {
2637  MRPT_START;
2638  using namespace std;
2639 
2640  // Summary of Results
2641  stringstream results_ss;
2642  results_ss << "Summary: " << std::endl;
2643  results_ss << this->header_sep << std::endl;
2644  results_ss << "\tProcessing time: "
2645  << m_time_logger.getMeanTime("proc_time") << std::endl;
2646  ;
2647  results_ss << "\tDataset Grab time: " << m_dataset_grab_time << std::endl;
2648  results_ss << "\tReal-time capable: "
2649  << (m_time_logger.getMeanTime("proc_time") < m_dataset_grab_time
2650  ? "TRUE"
2651  : "FALSE")
2652  << std::endl;
2653  results_ss << m_edge_counter.getAsString();
2654  results_ss << "\tNum of Nodes: " << m_graph.nodeCount() << std::endl;
2655  ;
2656 
2657  // Class configuration parameters
2658  std::string config_params = this->getParamsAsString();
2659 
2660  // time and output logging
2661  const std::string time_res = m_time_logger.getStatsAsText();
2662  const std::string output_res = this->getLogAsString();
2663 
2664  // merge the individual reports
2665  report_str->clear();
2666 
2667  *report_str += results_ss.str();
2668  *report_str += this->report_sep;
2669 
2670  *report_str += config_params;
2671  *report_str += this->report_sep;
2672 
2673  *report_str += time_res;
2674  *report_str += this->report_sep;
2675 
2676  *report_str += output_res;
2677  *report_str += this->report_sep;
2678 
2679  MRPT_END;
2680 }
2681 
2682 template <class GRAPH_T>
2684  std::map<std::string, int>* node_stats,
2685  std::map<std::string, int>* edge_stats,
2686  mrpt::system::TTimeStamp* timestamp /*=NULL*/)
2687 {
2688  MRPT_START;
2689  using namespace std;
2690  using namespace mrpt::graphslam::detail;
2691 
2692  ASSERTDEBMSG_(node_stats, "Invalid pointer to node_stats is given");
2693  ASSERTDEBMSG_(edge_stats, "Invalid pointer to edge_stats is given");
2694 
2695  if (m_nodeID_max == 0)
2696  {
2697  return false;
2698  }
2699 
2700  // fill the node stats
2701  (*node_stats)["nodes_total"] = m_nodeID_max + 1;
2702 
2703  // fill the edge stats
2704  for (CEdgeCounter::const_iterator it = m_edge_counter.cbegin();
2705  it != m_edge_counter.cend(); ++it)
2706  {
2707  (*edge_stats)[it->first] = it->second;
2708  }
2709 
2710  (*edge_stats)["loop_closures"] = m_edge_counter.getLoopClosureEdges();
2711  (*edge_stats)["edges_total"] = m_edge_counter.getTotalNumOfEdges();
2712 
2713  // fill the timestamp
2714  if (timestamp)
2715  {
2716  *timestamp = m_curr_timestamp;
2717  }
2718 
2719  return true;
2720  MRPT_END;
2721 }
2722 
2723 template <class GRAPH_T>
2725  const std::string& output_dir_fname)
2726 {
2727  MRPT_START;
2728  using namespace mrpt::system;
2729  using namespace mrpt;
2730 
2731  ASSERTDEBMSG_(
2732  directoryExists(output_dir_fname),
2733  format(
2734  "Output directory \"%s\" doesn't exist", output_dir_fname.c_str()));
2735 
2736  MRPT_LOG_INFO_STREAM("Generating detailed class report...");
2737  std::lock_guard<std::mutex> graph_lock(m_graph_section);
2738 
2739  std::string report_str;
2740  std::string fname;
2741  const std::string ext = ".log";
2742 
2743  { // CGraphSlamEngine
2744  report_str.clear();
2745  fname = output_dir_fname + "/" + m_class_name + ext;
2746  // initialize the output file - refer to the stream through the
2747  // m_out_streams map
2748  this->initResultsFile(fname);
2749  this->getDescriptiveReport(&report_str);
2750  m_out_streams[fname].printf("%s", report_str.c_str());
2751 
2752  // write the timings into a separate file
2753  const std::string time_res = m_time_logger.getStatsAsText();
2754  fname = output_dir_fname + "/" + "timings" + ext;
2755  this->initResultsFile(fname);
2756  m_out_streams[fname].printf("%s", time_res.c_str());
2757  }
2758  { // node_registrar
2759  report_str.clear();
2760  fname = output_dir_fname + "/" + "node_registrar" + ext;
2761  this->initResultsFile(fname);
2762  m_node_reg->getDescriptiveReport(&report_str);
2763  m_out_streams[fname].printf("%s", report_str.c_str());
2764  }
2765  { // edge_registrar
2766  report_str.clear();
2767  fname = output_dir_fname + "/" + "edge_registrar" + ext;
2768  this->initResultsFile(fname);
2769  m_edge_reg->getDescriptiveReport(&report_str);
2770  m_out_streams[fname].printf("%s", report_str.c_str());
2771  }
2772  { // optimizer
2773  report_str.clear();
2774  fname = output_dir_fname + "/" + "optimizer" + ext;
2775  this->initResultsFile(fname);
2776  m_optimizer->getDescriptiveReport(&report_str);
2777  m_out_streams[fname].printf("%s", report_str.c_str());
2778  }
2779 
2780  if (m_use_GT)
2781  { // slam evaluation metric
2782  report_str.clear();
2783  const std::string desc(
2784  "# File includes the evolution of the SLAM metric. Implemented "
2785  "metric computes the \"deformation energy\" that is needed to "
2786  "transfer the estimated trajectory into the ground-truth "
2787  "trajectory (computed as sum of the difference between estimated "
2788  "trajectory and ground truth consecutive poses See \"A comparison "
2789  "of SLAM algorithms based on a graph of relations - W.Burgard et "
2790  "al.\", for more details on the metric.\n");
2791 
2792  fname = output_dir_fname + "/" + "SLAM_evaluation_metric" + ext;
2793  this->initResultsFile(fname);
2794 
2795  m_out_streams[fname].printf("%s\n", desc.c_str());
2797  m_deformation_energy_vec.begin();
2798  vec_it != m_deformation_energy_vec.end(); ++vec_it)
2799  {
2800  m_out_streams[fname].printf("%f\n", *vec_it);
2801  }
2802  }
2803 
2804  MRPT_END;
2805 }
2806 template <class GRAPH_T>
2809  const std::string& model_name, const mrpt::img::TColor& model_color,
2810  const size_t model_size, const pose_t& init_pose)
2811 {
2812  using namespace mrpt::poses;
2813  using namespace mrpt::opengl;
2814  ASSERTDEBMSG_(!model_name.empty(), "Model name provided is empty.");
2815 
2817  this->initRobotModelVisualization();
2818  model->setName(model_name);
2819  model->setColor_u8(model_color);
2820  model->setScale(model_size);
2821  model->setPose(init_pose);
2822 
2823  return model;
2824 }
2825 
2826 // TODO - check this
2827 template <class GRAPH_T>
2829  std::vector<double>* vec_out) const
2830 {
2831  MRPT_START;
2832 
2833  ASSERTDEB_(vec_out);
2834  *vec_out = m_deformation_energy_vec;
2835 
2836  MRPT_END;
2837 }
2838 } // namespace mrpt::graphslam
2839 
2840 #endif /* end of include guard: CGRAPHSLAMENGINE_IMPL_H */
void updateOdometryVisualization()
Update odometry-only cloud with latest odometry estimation.
mrpt::opengl::CSetOfObjects::Ptr setCurrentPositionModel(const std::string &model_name, const mrpt::img::TColor &model_color=mrpt::img::TColor(0, 0, 0), const size_t model_size=1, const pose_t &init_pose=pose_t())
Set the opengl model that indicates the latest position of the trajectory at hand.
double Tac() noexcept
Stops the stopwatch.
Definition: CTicTac.cpp:90
Scalar * iterator
Definition: eigen_plugins.h:26
typename GRAPH_T::global_pose_t global_pose_t
void close()
Close the stream.
virtual void getNodeIDsOfEstimatedTrajectory(std::set< mrpt::graphs::TNodeID > *nodes_set) const
Return the list of nodeIDs which make up robot trajectory.
void queryObserverForEvents()
Query the observer instance for any user events.
#define MRPT_START
Definition: exceptions.h:262
void updateMapVisualization(const std::map< mrpt::graphs::TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > &nodes_to_laser_scans2D, bool full_update=false)
Update the map visualization based on the current graphSLAM state.
static time_point fromDouble(const double t) noexcept
Create a timestamp from its double representation.
Definition: Clock.cpp:51
void parseFile()
Parse the RGBD information file to gain information about the rawlog file contents.
void save3DScene(const std::string *fname_in=nullptr) const
Wrapper method around the COpenGLScene::saveToFile method.
VerbosityLevel
Enumeration of available verbosity levels.
std::string read_string(const std::string &section, const std::string &name, const std::string &defaultValue, bool failIfNotFound=false) const
const_iterator find(const KEY &key) const
Definition: ts_hash_map.h:217
A set of object, which are referenced to the coordinates framework established in this object...
Definition: CSetOfObjects.h:26
void updateGTVisualization()
Display the next ground truth position in the visualization window.
#define THROW_EXCEPTION(msg)
Definition: exceptions.h:41
Create a GUI window and display plots with MATLAB-like interfaces and commands.
void computeMap() const
Compute the map of the environment based on the recorded measurements.
mrpt::system::TTimeStamp getCurrentTime()
Returns the current (UTC) system time.
Definition: datetime.h:82
void updateSlamMetricVisualization()
Update the displayPlots window with the new information with regards to the metric.
Interface for implementing node registration classes.
double DEG2RAD(const double x)
Degrees to radians.
This class allows loading and storing values and vectors of different types from ".ini" files easily.
bool fileExists(const std::string &fileName)
Test if a given file (or directory) exists.
Definition: filesystem.cpp:127
A high-performance stopwatch, with typical resolution of nanoseconds.
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement, as from a time-of-flight range camera or any other RGBD sensor.
global_pose_t getCurrentRobotPosEstimation() const
Query CGraphSlamEngine instance for the current estimated robot position.
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
Definition: eigen_frwds.h:44
mrpt::system::TTimeStamp now()
A shortcut for system::getCurrentTime.
Definition: datetime.h:87
double pitch() const
Get the PITCH angle (in radians)
Definition: CPose3D.h:532
Interface for implementing edge registration classes.
double yaw() const
Get the YAW angle (in radians)
Definition: CPose3D.h:526
std::map< std::string, int >::const_iterator const_iterator
Definition: CEdgeCounter.h:32
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
std::string timeToString(const mrpt::system::TTimeStamp t)
Convert a timestamp into this textual form (UTC): HH:MM:SS.MMMMMM.
Definition: datetime.cpp:241
STL namespace.
virtual void setObjectPropsFromNodeID(const mrpt::graphs::TNodeID nodeID, mrpt::opengl::CSetOfObjects::Ptr &viz_object)
Set the properties of the map visual object based on the nodeID that it was produced by...
std::string fileNameStripInvalidChars(const std::string &filename, const char replacement_to_invalid_chars='_')
Replace invalid filename chars by underscores (&#39;_&#39;) or any other user-given char. ...
Definition: filesystem.cpp:328
GLsizei GLsizei GLuint * obj
Definition: glext.h:4070
#define MRPT_LOG_WARN_STREAM(__CONTENTS)
GLubyte GLubyte GLubyte GLubyte w
Definition: glext.h:4178
void tokenize(const std::string &inString, const std::string &inDelimiters, OUT_CONTAINER &outTokens, bool skipBlankTokens=true) noexcept
Tokenizes a string according to a set of delimiting characters.
mrpt::containers::ContainerReadOnlyProxyAccessor< mrpt::aligned_std_vector< char > > validRange
It&#39;s false (=0) on no reflected rays, referenced to elements in scan.
virtual void monitorNodeRegistration(bool registered=false, std::string class_name="Class")
Assert that the given nodes number matches the registered graph nodes, otherwise throw exception...
void loadParams(const std::string &fname)
Read the configuration variables from the .ini file specified by the user.
int read_int(const std::string &section, const std::string &name, int defaultValue, bool failIfNotFound=false) const
void computeSlamMetric(mrpt::graphs::TNodeID nodeID, size_t gt_index)
Compare the SLAM result (estimated trajectory) with the GT path.
void updateAllVisuals()
Wrapper around the deciders/optimizer updateVisuals methods.
This CStream derived class allow using a file as a read-only, binary stream.
mrpt::Clock::time_point TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
Definition: datetime.h:40
SLAM methods related to graphs of pose constraints.
static double accumulateAngleDiffs(const mrpt::poses::CPose2D &p1, const mrpt::poses::CPose2D &p2)
This base provides a set of functions for maths stuff.
static const std::string report_sep
T r() const
Return r coordinate of the quaternion.
Definition: CQuaternion.h:85
typename GRAPH_T::constraint_t::type_value pose_t
Type of underlying poses (2D/3D).
mrpt::containers::ContainerReadOnlyProxyAccessor< mrpt::aligned_std_vector< float > > scan
The range values of the scan, in meters.
void execDijkstraNodesEstimation()
Wrapper around the GRAPH_T::dijkstra_nodes_estimate.
void updateIntensityImageViewport()
In RGB-D TUM Datasets update the Intensity image displayed in a seperate viewport.
const GLubyte * c
Definition: glext.h:6313
_u8 model
Definition: rplidar_cmd.h:19
#define ASSERTDEB_EQUAL_(__A, __B)
Definition: exceptions.h:211
GLint GLvoid * img
Definition: glext.h:3763
bool readLine(std::string &str)
Reads one string line from the file (until a new-line character)
static uint64_t getCurrentTime()
Definition: Clock.cpp:22
std::deque< CObservation::Ptr >::const_iterator const_iterator
You can use CSensoryFrame::begin to get a iterator to the first element.
This namespace contains representation of robot actions and observations.
This object renders a 2D laser scan by means of three elements: the points, the line along end-points...
virtual void updateCurrPosViewport()
Update the viewport responsible for displaying the graph-building procedure in the estimated position...
mrpt::opengl::CSetOfObjects::Ptr initRobotModelVisualizationInternal(const mrpt::poses::CPose2D &p_unused)
Method to help overcome the partial template specialization restriction of C++.
CGraphSlamEngine(const std::string &config_file, const std::string &rawlog_fname="", const std::string &fname_GT="", mrpt::graphslam::CWindowManager *win_manager=NULL, mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_T > *node_reg=NULL, mrpt::graphslam::deciders::CEdgeRegistrationDecider< GRAPH_T > *edge_reg=NULL, mrpt::graphslam::optimizers::CGraphSlamOptimizer< GRAPH_T > *optimizer=NULL)
Constructor of CGraphSlamEngine class template.
void updateEstimatedTrajectoryVisualization(bool full_update=false)
Update the Esstimated robot trajectory with the latest estimated robot position.
#define MRPT_LOG_DEBUG_STREAM(__CONTENTS)
Use: MRPT_LOG_DEBUG_STREAM("Var=" << value << " foo=" << foo_var);
GLsizei const GLchar ** string
Definition: glext.h:4101
T wrapToPi(T a)
Modifies the given angle to translate it into the ]-pi,pi] range.
Definition: wrap2pi.h:51
void saveGraph(const std::string *fname_in=nullptr) const
Wrapper method around the GRAPH_T::saveToTextFile method.
virtual ~CGraphSlamEngine()
Default Destructor.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
void getDescriptiveReport(std::string *report_str) const
Fill the provided string with a detailed report of the class state.
double roll() const
Get the ROLL angle (in radians)
Definition: CPose3D.h:538
static const std::string header_sep
Separator string to be used in debugging messages.
CSetOfObjects::Ptr RobotPioneer()
Returns a representation of a Pioneer II mobile base.
virtual mrpt::poses::CPose3D getLSPoseForGridMapVisualization(const mrpt::graphs::TNodeID nodeID) const
return the 3D Pose of a LaserScan that is to be visualized.
void pause(const std::string &msg=std::string("Press any key to continue...")) noexcept
Shows the message "Press any key to continue" (or other custom message) to the current standard outpu...
Definition: os.cpp:428
virtual bool _execGraphSlamStep(mrpt::obs::CActionCollection::Ptr &action, mrpt::obs::CSensoryFrame::Ptr &observations, mrpt::obs::CObservation::Ptr &observation, size_t &rawlog_entry)
Main class method responsible for parsing each measurement and for executing graphSLAM.
mrpt::opengl::CSetOfObjects::Ptr initRobotModelVisualization()
#define MRPT_LOG_INFO_STREAM(__CONTENTS)
#define ASSERTDEBMSG_(f, __ERROR_MSG)
Definition: exceptions.h:208
void printParams() const
Print the problem parameters to the console for verification.
auto dir
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
static void readGTFile(const std::string &fname_GT, std::vector< mrpt::poses::CPose2D > *gt_poses, std::vector< mrpt::system::TTimeStamp > *gt_timestamps=NULL)
Parse the ground truth .txt file and fill in the corresponding gt_poses vector.
virtual GRAPH_T::global_poses_t getRobotEstimatedTrajectory() const
GLdouble GLdouble GLdouble r
Definition: glext.h:3705
static mrpt::system::TTimeStamp getTimeStamp(const mrpt::obs::CActionCollection::Ptr action, const mrpt::obs::CSensoryFrame::Ptr observations, const mrpt::obs::CObservation::Ptr observation)
Fill the TTimestamp in a consistent manner.
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
Definition: CPose2D.h:38
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:86
std::string dateTimeToString(const mrpt::system::TTimeStamp t)
Convert a timestamp into this textual form (UTC time): YEAR/MONTH/DAY,HH:MM:SS.MMM.
Definition: datetime.cpp:147
#define ASSERTDEB_(f)
Defines an assertion mechanism - only when compiled in debug.
Definition: exceptions.h:205
bool read_bool(const std::string &section, const std::string &name, bool defaultValue, bool failIfNotFound=false) const
CSetOfObjects::Ptr CornerXYZ(float scale=1.0)
Returns three arrows representing a X,Y,Z 3D corner.
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
Definition: format.cpp:16
const double & phi() const
Get the phi angle of the 2D pose (in radians)
Definition: CPose2D.h:80
#define IS_CLASS(ptrObj, class_name)
Evaluates to true if the given pointer to an object (derived from mrpt::rtti::CObject) is of the give...
Definition: CObject.h:102
#define MRPT_END
Definition: exceptions.h:266
A RGB color - floats in the range [0,1].
Definition: TColor.h:77
void decimateLaserScan(mrpt::obs::CObservation2DRangeScan &laser_scan_in, mrpt::obs::CObservation2DRangeScan *laser_scan_out, const int keep_every_n_entries=2)
Cut down on the size of the given laser scan.
void getDeformationEnergyVector(std::vector< double > *vec_out) const
Fill the given vector with the deformation energy values computed for the SLAM evaluation metric...
The namespace for 3D scene representation and rendering.
Definition: CGlCanvasBase.h:15
uint64_t TNodeID
A generic numeric type for unique IDs of nodes or entities.
Definition: TNodeID.h:16
typename GRAPH_T::constraint_t constraint_t
Type of graph constraints.
void loadFromVectors(size_t nRays, const float *scanRanges, const char *scanValidity)
void getMap(mrpt::maps::COccupancyGridMap2D::Ptr map, mrpt::system::TTimeStamp *acquisition_time=NULL) const
GLenum GLint GLint y
Definition: glext.h:3538
std::string trim(const std::string &str)
Removes leading and trailing spaces.
bool execGraphSlamStep(mrpt::obs::CObservation::Ptr &observation, size_t &rawlog_entry)
Wrapper method around _execGraphSlamStep.
Classes for creating GUI windows for 2D and 3D visualization.
Definition: about_box.h:14
bool getGraphSlamStats(std::map< std::string, int > *node_stats, std::map< std::string, int > *edge_stats, mrpt::system::TTimeStamp *timestamp=NULL)
Fill the given maps with stats regarding the overall execution of graphslam.
#define INVALID_NODEID
Definition: TNodeID.h:19
std::string getParamsAsString() const
Wrapper around getParamsAsString.
bool directoryExists(const std::string &fileName)
Test if a given directory exists (it fails if the given path refers to an existing file)...
Definition: filesystem.cpp:136
static void readGTFileRGBD_TUM(const std::string &fname_GT, std::vector< mrpt::poses::CPose2D > *gt_poses, std::vector< mrpt::system::TTimeStamp > *gt_timestamps=NULL)
Parse the ground truth .txt file and fill in the corresponding m_GT_poses vector. ...
double timeDifference(const mrpt::system::TTimeStamp t_first, const mrpt::system::TTimeStamp t_later)
Returns the time difference from t1 to t2 (positive if t2 is posterior to t1), in seconds...
Definition: datetime.h:122
GLuint res
Definition: glext.h:7268
A RGB color - 8bit.
Definition: TColor.h:20
An observation of the current (cumulative) odometry for a wheeled robot.
GLenum GLint x
Definition: glext.h:3538
A quaternion, which can represent a 3D rotation as pair , with a real part "r" and a 3D vector ...
Definition: CQuaternion.h:44
void Tic() noexcept
Starts the stopwatch.
Definition: CTicTac.cpp:79
std::string extractFileName(const std::string &filePath)
Extract just the name (without extension) of a filename from a complete path plus name plus extension...
Definition: filesystem.cpp:61
#define ASSERT_FILE_EXISTS_(FIL)
Definition: filesystem.h:21
A set of independent lines (or segments), one line with its own start and end positions (X...
Definition: CSetOfLines.h:31
#define MRPT_LOG_ERROR_STREAM(__CONTENTS)
bool strCmpI(const std::string &s1, const std::string &s2)
Return true if the two strings are equal (case insensitive)
GLfloat GLfloat p
Definition: glext.h:6305
bool insertObservation(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose=NULL)
Insert the observation information into this map.
Definition: CMetricMap.cpp:95
static void setImagesPathBase(const std::string &path)
Definition: CImage.cpp:54
const Scalar * const_iterator
Definition: eigen_plugins.h:27
Internal auxiliary classes.
Definition: levmarq_impl.h:17
void dumpVisibilityErrorMsg(std::string viz_flag, int sleep_time=500)
Wrapper method that used for printing error messages in a consistent manner.
bool fileOpenCorrectly() const
Returns true if the file was open without errors.
#define INVALID_TIMESTAMP
Represents an invalid timestamp, where applicable.
Definition: datetime.h:43
std::string extractFileDirectory(const std::string &filePath)
Extract the whole path (the directory) of a filename from a complete path plus name plus extension...
Definition: filesystem.cpp:77
void updateRangeImageViewport()
In RGB-D TUM Datasets update the Range image displayed in a seperate viewport.
Class acts as a container for storing pointers to mrpt::gui::CDisplayWindow3D, mrpt::graphslam::CWind...
void generateReportFiles(const std::string &output_dir_fname_in)
Generate and write to a corresponding report for each of the respective self/decider/optimizer classe...
A class for storing images as grayscale or RGB bitmaps.
Definition: img/CImage.h:130
A cloud of points, all with the same color or each depending on its value along a particular coordina...
Definition: CPointCloud.h:43
void initResultsFile(const std::string &fname)
Automate the creation and initialization of a results file relevant to the application.
void initClass()
General initialization method to call from the Class Constructors.
static const std::string & getImagesPathBase()
By default, ".".
Definition: CImage.cpp:53



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 7d5e6d718 Fri Aug 24 01:51:28 2018 +0200 at lun nov 2 08:35:50 CET 2020