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



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019