10 #ifndef CGRAPHSLAMENGINE_IMPL_H 11 #define CGRAPHSLAMENGINE_IMPL_H 23 template <
class GRAPH_T>
25 template <
class GRAPH_T>
31 template <
class GRAPH_T>
43 : m_node_reg(node_reg),
45 m_optimizer(optimizer),
46 m_enable_visuals(win_manager != nullptr),
47 m_config_fname(config_file),
48 m_rawlog_fname(rawlog_fname),
51 m_win_manager(win_manager),
52 m_paused_message(
"Program is paused. Press \"p/P\" to resume."),
53 m_text_index_paused_message(345),
54 m_odometry_color(0, 0, 255),
55 m_GT_color(0, 255, 0),
56 m_estimated_traj_color(255, 165, 0),
57 m_optimized_map_color(255, 0, 0),
58 m_current_constraint_type_color(255, 255, 255),
59 m_robot_model_size(1),
60 m_class_name(
"CGraphSlamEngine"),
61 m_is_first_time_node_reg(true)
66 template <
class GRAPH_T>
73 "In Destructor: Deleting CGraphSlamEngine instance...");
93 template <
class GRAPH_T>
94 typename GRAPH_T::global_pose_t
97 std::lock_guard<std::mutex> graph_lock(m_graph_section);
98 return m_node_reg->getCurrentRobotPosEstimation();
101 template <
class GRAPH_T>
102 typename GRAPH_T::global_poses_t
105 std::lock_guard<std::mutex> graph_lock(m_graph_section);
106 return m_graph.nodes;
109 template <
class GRAPH_T>
111 std::set<mrpt::graphs::TNodeID>* nodes_set)
const 114 m_graph.getAllNodes(*nodes_set);
117 template <
class GRAPH_T>
121 using namespace mrpt;
126 m_time_logger.setName(m_class_name);
127 this->logging_enable_keep_record =
true;
128 this->setLoggerName(m_class_name);
140 m_supported_constraint_types.push_back(
"CPosePDFGaussianInf");
141 m_supported_constraint_types.push_back(
"CPose3DPDFGaussianInf");
144 const string c_str(
c.GetRuntimeClass()->className);
148 m_supported_constraint_types.begin(),
149 m_supported_constraint_types.end(),
150 c_str) != m_supported_constraint_types.end());
159 "Given graph class " << c_str
160 <<
" has not been tested consistently yet." 161 <<
"Proceed at your own risk.");
166 m_current_constraint_type = c_str;
167 m_current_constraint_type =
"Constraints: " + m_current_constraint_type;
171 if (m_enable_visuals)
173 m_win = m_win_manager->win;
174 m_win_observer = m_win_manager->observer;
179 m_win_observer =
nullptr;
187 m_win_plot =
nullptr;
189 m_observation_only_dataset =
false;
190 m_request_to_exit =
false;
196 m_GT_poses_index = 0;
200 m_node_reg->setGraphPtr(&m_graph);
201 m_edge_reg->setGraphPtr(&m_graph);
202 m_optimizer->setGraphPtr(&m_graph);
206 if (m_enable_visuals)
208 m_node_reg->setWindowManagerPtr(m_win_manager);
209 m_edge_reg->setWindowManagerPtr(m_win_manager);
210 m_optimizer->setWindowManagerPtr(m_win_manager);
211 m_edge_counter.setWindowManagerPtr(m_win_manager);
215 m_node_reg->setCriticalSectionPtr(&m_graph_section);
216 m_edge_reg->setCriticalSectionPtr(&m_graph_section);
217 m_optimizer->setCriticalSectionPtr(&m_graph_section);
221 this->loadParams(m_config_fname);
223 if (!m_enable_visuals)
226 m_visualize_odometry_poses = 0;
229 m_visualize_estimated_trajectory = 0;
230 m_visualize_SLAM_metric = 0;
231 m_enable_curr_pos_viewport = 0;
232 m_enable_range_viewport = 0;
233 m_enable_intensity_viewport = 0;
236 m_use_GT = !m_fname_GT.empty();
242 this->alignOpticalWithMRPTFrame();
247 this->readGTFile(m_fname_GT, &m_GT_poses);
255 "Ground truth file was not provided. Switching the related " 256 "visualization parameters off...");
258 m_visualize_SLAM_metric = 0;
262 if (m_enable_visuals)
264 m_win_manager->assignTextMessageParameters(
265 &m_offset_y_timestamp, &m_text_index_timestamp);
270 this->initMapVisualization();
275 if (m_enable_visuals)
278 if (m_visualize_odometry_poses)
280 this->initOdometryVisualization();
285 this->initGTVisualization();
288 this->initEstimatedTrajectoryVisualization();
290 if (m_enable_curr_pos_viewport)
292 this->initCurrPosViewport();
305 m_img_external_storage_dir =
306 rawlog_dir + rawlog_fname_noext +
"_Images/";
313 if (m_enable_range_viewport)
315 this->initRangeImageViewport();
317 if (m_enable_intensity_viewport)
319 this->initIntensityImageViewport();
323 if (m_enable_visuals)
328 obj->setFrequency(5);
329 obj->enableTickMarks();
330 obj->setAxisLimits(-10, -10, -10, 10, 10, 10);
331 obj->setName(
"axis");
334 m_win->unlockAccess3DScene();
335 m_win->forceRepaint();
339 if (m_enable_visuals)
342 m_keystroke_pause_exec =
"p";
343 m_keystroke_odometry =
"o";
344 m_keystroke_GT =
"g";
345 m_keystroke_estimated_trajectory =
"t";
346 m_keystroke_map =
"m";
349 m_win_observer->registerKeystroke(
350 m_keystroke_pause_exec,
"Pause/Resume program execution");
351 m_win_observer->registerKeystroke(
352 m_keystroke_odometry,
"Toggle Odometry visualization");
353 m_win_observer->registerKeystroke(
354 m_keystroke_GT,
"Toggle Ground-Truth visualization");
355 m_win_observer->registerKeystroke(
356 m_keystroke_estimated_trajectory,
357 "Toggle Estimated trajectory visualization");
358 m_win_observer->registerKeystroke(
359 m_keystroke_map,
"Toggle Map visualization");
363 vector<string> vec_edge_types;
364 vec_edge_types.push_back(
"Odometry");
365 vec_edge_types.push_back(
"ICP2D");
366 vec_edge_types.push_back(
"ICP3D");
369 cit != vec_edge_types.end(); ++cit)
371 m_edge_counter.addEdgeType(*cit);
375 if (m_enable_visuals)
378 double offset_y_total_edges, offset_y_loop_closures;
379 int text_index_total_edges, text_index_loop_closures;
381 m_win_manager->assignTextMessageParameters(
382 &offset_y_total_edges, &text_index_total_edges);
385 map<string, double> name_to_offset_y;
386 map<string, int> name_to_text_index;
388 it != vec_edge_types.end(); ++it)
390 m_win_manager->assignTextMessageParameters(
391 &name_to_offset_y[*it], &name_to_text_index[*it]);
394 m_win_manager->assignTextMessageParameters(
395 &offset_y_loop_closures, &text_index_loop_closures);
398 m_edge_counter.setTextMessageParams(
399 name_to_offset_y, name_to_text_index, offset_y_total_edges,
400 text_index_total_edges, offset_y_loop_closures,
401 text_index_loop_closures);
405 if (m_enable_visuals)
407 m_win_manager->assignTextMessageParameters(
408 &m_offset_y_current_constraint_type,
409 &m_text_index_current_constraint_type);
410 m_win_manager->addTextMessage(
411 m_offset_x_left, -m_offset_y_current_constraint_type,
412 m_current_constraint_type,
414 m_text_index_current_constraint_type);
418 if (m_enable_visuals)
420 std::lock_guard<std::mutex> graph_lock(m_graph_section);
421 m_time_logger.enter(
"Visuals");
422 m_node_reg->initializeVisuals();
423 m_edge_reg->initializeVisuals();
424 m_optimizer->initializeVisuals();
425 m_time_logger.leave(
"Visuals");
433 mrpt::make_aligned_shared<mrpt::maps::COccupancyGridMap2D>();
444 gridmap->insertionOptions.maxOccupancyUpdateCertainty = 0.8f;
445 gridmap->insertionOptions.maxDistanceInsertion = 5;
446 gridmap->insertionOptions.wideningBeamsWithDistance =
true;
447 gridmap->insertionOptions.decimation = 2;
449 m_gridmap_cached = gridmap;
450 m_map_is_cached =
false;
456 mrpt::make_aligned_shared<mrpt::maps::COctoMap>();
460 octomap->insertionOptions.setOccupancyThres(0.5);
461 octomap->insertionOptions.setProbHit(0.7);
462 octomap->insertionOptions.setProbMiss(0.4);
463 octomap->insertionOptions.setClampingThresMin(0.1192);
464 octomap->insertionOptions.setClampingThresMax(0.971);
467 m_map_is_cached =
false;
474 m_info_params.setRawlogFile(m_rawlog_fname);
475 m_info_params.parseFile();
477 int num_of_objects = std::atoi(
478 m_info_params.fields[
"Overall number of objects"].c_str());
479 m_GT_poses_step = m_GT_poses.size() / num_of_objects;
482 "Overall number of objects in rawlog: " << num_of_objects);
484 "Setting the Ground truth read step to: " << m_GT_poses_step);
486 catch (std::exception& e)
492 m_curr_deformation_energy = 0;
493 if (m_visualize_SLAM_metric)
495 this->initSlamMetricVisualization();
499 if (m_enable_visuals)
501 this->m_win->addTextMessage(
503 m_text_index_paused_message);
509 template <
class GRAPH_T>
518 return this->_execGraphSlamStep(
519 action, observations, observation, rawlog_entry);
522 template <
class GRAPH_T>
531 using namespace mrpt;
538 m_time_logger.enter(
"proc_time");
542 format(
"\nConfig file is not read yet.\nExiting... \n"));
548 m_init_timestamp = getTimeStamp(action, observations, observation);
554 m_observation_only_dataset =
true;
560 m_observation_only_dataset =
false;
563 action->getFirstMovementEstimationMean(increment_pose_3d);
564 pose_t increment_pose(increment_pose_3d);
565 m_curr_odometry_only_pose += increment_pose;
573 bool registered_new_node;
575 std::lock_guard<std::mutex> graph_lock(m_graph_section);
576 m_time_logger.enter(
"node_registrar");
577 registered_new_node =
578 m_node_reg->updateState(action, observations, observation);
579 m_time_logger.leave(
"node_registrar");
584 getObservation<CObservation2DRangeScan>(observations, observation);
587 m_last_laser_scan2D = scan;
589 if (!m_first_laser_scan2D)
591 m_first_laser_scan2D = m_last_laser_scan2D;
596 if (registered_new_node)
600 if (m_is_first_time_node_reg)
602 std::lock_guard<std::mutex> graph_lock(m_graph_section);
604 if (m_graph.nodeCount() != 2)
607 "Expected [2] new registered nodes" 608 <<
" but got [" << m_graph.nodeCount() <<
"]");
612 m_nodes_to_laser_scans2D.insert(
613 make_pair(m_nodeID_max, m_first_laser_scan2D));
615 m_is_first_time_node_reg =
false;
622 m_edge_counter.addEdge(
"Odometry");
624 this->monitorNodeRegistration(
625 registered_new_node,
"NodeRegistrationDecider");
631 std::lock_guard<std::mutex> graph_lock(m_graph_section);
633 m_time_logger.enter(
"edge_registrar");
634 m_edge_reg->updateState(action, observations, observation);
635 m_time_logger.leave(
"edge_registrar");
637 this->monitorNodeRegistration(
638 registered_new_node,
"EdgeRegistrationDecider");
641 std::lock_guard<std::mutex> graph_lock(m_graph_section);
643 m_time_logger.enter(
"optimizer");
644 m_optimizer->updateState(action, observations, observation);
645 m_time_logger.leave(
"optimizer");
647 this->monitorNodeRegistration(registered_new_node,
"GraphSlamOptimizer");
650 m_curr_timestamp = getTimeStamp(action, observations, observation);
663 m_curr_odometry_only_pose =
pose_t(obs_odometry->odometry);
664 m_odometry_poses.push_back(m_curr_odometry_only_pose);
668 m_last_laser_scan3D =
681 action->getFirstMovementEstimationMean(increment_pose_3d);
682 pose_t increment_pose(increment_pose_3d);
683 m_curr_odometry_only_pose += increment_pose;
684 m_odometry_poses.push_back(m_curr_odometry_only_pose);
687 if (registered_new_node)
689 this->execDijkstraNodesEstimation();
692 m_nodes_to_laser_scans2D[m_nodeID_max] = m_last_laser_scan2D;
694 if (m_enable_visuals && m_visualize_map)
696 std::lock_guard<std::mutex> graph_lock(m_graph_section);
698 bool full_update =
true;
699 this->updateMapVisualization(m_nodes_to_laser_scans2D, full_update);
703 if (m_enable_visuals)
705 this->updateAllVisuals();
709 std::map<std::string, int> edge_types_to_nums;
710 m_edge_reg->getEdgesStats(&edge_types_to_nums);
711 if (edge_types_to_nums.size())
714 edge_types_to_nums.begin();
715 it != edge_types_to_nums.end(); ++it)
720 m_edge_counter.setLoopClosureEdgesManually(it->second);
724 m_edge_counter.setEdgesManually(it->first, it->second);
731 if (m_enable_curr_pos_viewport)
733 updateCurrPosViewport();
736 if (m_enable_visuals)
738 bool full_update =
true;
739 m_time_logger.enter(
"Visuals");
740 this->updateEstimatedTrajectoryVisualization(full_update);
741 m_time_logger.leave(
"Visuals");
748 m_time_logger.enter(
"SLAM_metric");
749 this->computeSlamMetric(m_nodeID_max, m_GT_poses_index);
750 m_time_logger.leave(
"SLAM_metric");
751 if (m_visualize_SLAM_metric)
753 m_time_logger.enter(
"Visuals");
754 this->updateSlamMetricVisualization();
755 m_time_logger.leave(
"Visuals");
760 m_map_is_cached =
false;
767 m_time_logger.enter(
"Visuals");
771 if (m_enable_visuals)
775 m_win_manager->addTextMessage(
776 m_offset_x_left, -m_offset_y_timestamp,
778 "Simulated time: %s",
781 m_text_index_timestamp);
785 m_win_manager->addTextMessage(
786 m_offset_x_left, -m_offset_y_timestamp,
791 m_text_index_timestamp);
796 if (m_visualize_odometry_poses && m_odometry_poses.size())
798 this->updateOdometryVisualization();
807 if (m_enable_visuals)
809 this->updateGTVisualization();
812 m_GT_poses_index += m_GT_poses_step;
816 if (m_observation_only_dataset)
818 if (rawlog_entry % 2 == 0)
820 if (m_enable_visuals)
822 this->updateGTVisualization();
825 m_GT_poses_index += m_GT_poses_step;
832 if (m_enable_visuals)
834 this->updateGTVisualization();
837 m_GT_poses_index += m_GT_poses_step;
845 if (m_enable_range_viewport && m_last_laser_scan3D)
847 this->updateRangeImageViewport();
850 if (m_enable_intensity_viewport && m_last_laser_scan3D)
852 this->updateIntensityImageViewport();
857 if (m_enable_visuals)
859 this->queryObserverForEvents();
861 m_time_logger.leave(
"Visuals");
863 m_dataset_grab_time =
865 m_time_logger.leave(
"proc_time");
867 return !m_request_to_exit;
871 template <
class GRAPH_T>
875 std::lock_guard<std::mutex> graph_lock(m_graph_section);
876 m_time_logger.enter(
"dijkstra_nodes_estimation");
877 m_graph.dijkstra_nodes_estimate();
878 m_time_logger.leave(
"dijkstra_nodes_estimation");
882 template <
class GRAPH_T>
887 using namespace mrpt;
889 std::lock_guard<std::mutex> graph_lock(m_graph_section);
890 size_t listed_nodeCount =
896 listed_nodeCount == m_graph.nodeCount(),
898 "listed_nodeCount [%lu] != nodeCount() [%lu]",
899 static_cast<unsigned long>(listed_nodeCount),
900 static_cast<unsigned long>(m_graph.nodeCount())));
904 if (listed_nodeCount != m_graph.nodeCount())
907 class_name <<
" illegally added new nodes to the graph " 908 <<
", wanted to see [" << listed_nodeCount
909 <<
"] but saw [" << m_graph.nodeCount() <<
"]");
911 format(
"Illegal node registration by %s.", class_name.c_str()));
917 template <
class GRAPH_T>
926 map = mrpt::make_aligned_shared<mrpt::maps::COccupancyGridMap2D>();
930 if (!m_map_is_cached)
934 map->copyMapContentFrom(*m_gridmap_cached);
937 if (acquisition_time)
939 *acquisition_time = m_map_acq_time;
944 template <
class GRAPH_T>
952 if (!m_map_is_cached)
961 if (acquisition_time)
963 *acquisition_time = m_map_acq_time;
969 template <
class GRAPH_T>
974 using namespace mrpt;
978 std::lock_guard<std::mutex> graph_lock(m_graph_section);
980 if (!constraint_t::is_3D())
991 m_nodes_to_laser_scans2D.begin();
992 it != m_nodes_to_laser_scans2D.end(); ++it)
1001 "LaserScan of nodeID: %lu is not present.",
1002 static_cast<unsigned long>(curr_node)));
1005 CPose3D scan_pose = getLSPoseForGridMapVisualization(curr_node);
1008 gridmap->insertObservation(curr_laser_scan.get(), &scan_pose);
1011 m_map_is_cached =
true;
1017 THROW_EXCEPTION(
"Not Implemented Yet. Method is to compute a COctoMap");
1024 template <
class GRAPH_T>
1031 mrpt::format(
"\nConfiguration file not found: \n%s\n", fname.c_str()));
1039 m_user_decides_about_output_dir = cfg_file.
read_bool(
1040 "GeneralConfiguration",
"user_decides_about_output_dir",
false,
false);
1042 "GeneralConfiguration",
"ground_truth_file_format",
"NavSimul",
false);
1045 int min_verbosity_level =
1046 cfg_file.
read_int(
"GeneralConfiguration",
"class_verbosity", 1,
false);
1054 "VisualizationParameters",
"visualize_map",
true,
false);
1057 m_visualize_odometry_poses = cfg_file.
read_bool(
1058 "VisualizationParameters",
"visualize_odometry_poses",
true,
false);
1059 m_visualize_estimated_trajectory = cfg_file.
read_bool(
1060 "VisualizationParameters",
"visualize_estimated_trajectory",
true,
1065 "VisualizationParameters",
"visualize_ground_truth",
true,
false);
1067 m_visualize_SLAM_metric = cfg_file.
read_bool(
1068 "VisualizationParameters",
"visualize_SLAM_metric",
true,
false);
1071 m_enable_curr_pos_viewport = cfg_file.
read_bool(
1072 "VisualizationParameters",
"enable_curr_pos_viewport",
true,
false);
1073 m_enable_range_viewport = cfg_file.
read_bool(
1074 "VisualizationParameters",
"enable_range_viewport",
false,
false);
1075 m_enable_intensity_viewport = cfg_file.
read_bool(
1076 "VisualizationParameters",
"enable_intensity_viewport",
false,
false);
1078 m_node_reg->loadParams(fname);
1079 m_edge_reg->loadParams(fname);
1080 m_optimizer->loadParams(fname);
1082 m_has_read_config =
true;
1085 template <
class GRAPH_T>
1091 this->getParamsAsString(&str);
1096 template <
class GRAPH_T>
1101 using namespace std;
1103 stringstream ss_out;
1106 <<
"\n------------[ Graphslam_engine Problem Parameters ]------------" 1108 ss_out <<
"Config filename = " << m_config_fname
1111 ss_out <<
"Ground Truth File format = " << m_GT_file_format
1113 ss_out <<
"Ground Truth filename = " << m_fname_GT << std::endl;
1115 ss_out <<
"Visualize odometry = " 1116 << (m_visualize_odometry_poses ?
"TRUE" :
"FALSE") << std::endl;
1117 ss_out <<
"Visualize estimated trajectory = " 1118 << (m_visualize_estimated_trajectory ?
"TRUE" :
"FALSE")
1120 ss_out <<
"Visualize map = " 1121 << (m_visualize_map ?
"TRUE" :
"FALSE") << std::endl;
1122 ss_out <<
"Visualize Ground Truth = " 1123 << (m_visualize_GT ?
"TRUE" :
"FALSE") << std::endl;
1125 ss_out <<
"Visualize SLAM metric plot = " 1126 << (m_visualize_SLAM_metric ?
"TRUE" :
"FALSE") << std::endl;
1128 ss_out <<
"Enable curr. position viewport = " 1129 << (m_enable_curr_pos_viewport ?
"TRUE" :
"FALSE") << endl;
1130 ss_out <<
"Enable range img viewport = " 1131 << (m_enable_range_viewport ?
"TRUE" :
"FALSE") << endl;
1132 ss_out <<
"Enable intensity img viewport = " 1133 << (m_enable_intensity_viewport ?
"TRUE" :
"FALSE") << endl;
1135 ss_out <<
"-----------------------------------------------------------" 1137 ss_out << std::endl;
1140 *params_out = ss_out.str();
1145 template <
class GRAPH_T>
1149 std::cout << getParamsAsString();
1151 m_node_reg->printParams();
1152 m_edge_reg->printParams();
1153 m_optimizer->printParams();
1158 template <
class GRAPH_T>
1162 using namespace std;
1173 m_out_streams[fname].open(fname);
1175 m_out_streams[fname].fileOpenCorrectly(),
1176 mrpt::format(
"\nError while trying to open %s\n", fname.c_str()));
1180 m_out_streams[fname].printf(
"# Mobile Robot Programming Toolkit (MRPT)\n");
1181 m_out_streams[fname].printf(
"# http::/www.mrpt.org\n");
1182 m_out_streams[fname].printf(
"# GraphSlamEngine Application\n");
1183 m_out_streams[fname].printf(
1184 "# Automatically generated file - %s: %s\n", time_spec.c_str(),
1185 cur_date_str.c_str());
1186 m_out_streams[fname].printf(
"%s\n\n", sep.c_str());
1191 template <
class GRAPH_T>
1201 viewp_range = scene->createViewport(
"viewp_range");
1203 m_win_manager->assignViewportParameters(&
x, &
y, &
w, &h);
1204 viewp_range->setViewportPosition(
x,
y, h,
w);
1206 m_win->unlockAccess3DScene();
1207 m_win->forceRepaint();
1212 template <
class GRAPH_T>
1216 std::lock_guard<std::mutex> graph_lock(m_graph_section);
1217 m_time_logger.enter(
"Visuals");
1219 m_node_reg->updateVisuals();
1220 m_edge_reg->updateVisuals();
1221 m_optimizer->updateVisuals();
1223 m_time_logger.leave(
"Visuals");
1227 template <
class GRAPH_T>
1235 if (m_last_laser_scan3D->hasRangeImage)
1243 m_last_laser_scan3D->load();
1244 range2D = m_last_laser_scan3D->rangeImage *
1246 img.setFromMatrix(range2D);
1250 viewp_range->setImageView(
img);
1251 m_win->unlockAccess3DScene();
1252 m_win->forceRepaint();
1258 template <
class GRAPH_T>
1268 viewp_intensity = scene->createViewport(
"viewp_intensity");
1270 m_win_manager->assignViewportParameters(&
x, &
y, &
w, &h);
1271 viewp_intensity->setViewportPosition(
x,
y,
w, h);
1273 m_win->unlockAccess3DScene();
1274 m_win->forceRepaint();
1278 template <
class GRAPH_T>
1285 if (m_last_laser_scan3D->hasIntensityImage)
1290 m_last_laser_scan3D->load();
1291 img = m_last_laser_scan3D->intensityImage;
1295 scene->getViewport(
"viewp_intensity");
1296 viewp_intensity->setImageView(
img);
1297 m_win->unlockAccess3DScene();
1298 m_win->forceRepaint();
1304 template <
class GRAPH_T>
1309 return this->initRobotModelVisualizationInternal(
p);
1312 template <
class GRAPH_T>
1321 template <
class GRAPH_T>
1329 template <
class GRAPH_T>
1338 scene->createViewport(
"curr_robot_pose_viewport");
1340 viewp->setCloneView(
"main");
1342 m_win_manager->assignViewportParameters(&
x, &
y, &
w, &h);
1343 viewp->setViewportPosition(
x,
y, h,
w);
1344 viewp->setTransparent(
false);
1345 viewp->getCamera().setAzimuthDegrees(90);
1346 viewp->getCamera().setElevationDegrees(90);
1347 viewp->setCustomBackgroundColor(
1349 viewp->getCamera().setZoomDistance(30);
1350 viewp->getCamera().setOrthogonal();
1352 m_win->unlockAccess3DScene();
1353 m_win->forceRepaint();
1358 template <
class GRAPH_T>
1368 global_pose_t curr_robot_pose = this->getCurrentRobotPosEstimation();
1372 viewp->getCamera().setPointingAt(
CPose3D(curr_robot_pose));
1374 m_win->unlockAccess3DScene();
1375 m_win->forceRepaint();
1381 template <
class GRAPH_T>
1383 const std::string& fname_GT, std::vector<mrpt::poses::CPose2D>* gt_poses,
1384 std::vector<mrpt::system::TTimeStamp>* gt_timestamps )
1387 using namespace std;
1394 "\nGround-truth file %s was not found.\n" 1395 "Either specify a valid ground-truth filename or set set the " 1396 "m_visualize_GT flag to false\n",
1401 ASSERTDEBMSG_(gt_poses,
"\nNo valid std::vector<pose_t>* was given\n");
1406 for (
size_t line_num = 0; file_GT.
readLine(curr_line); line_num++)
1408 vector<string> curr_tokens;
1413 curr_tokens.size() == constraint_t::state_length + 1,
1414 "\nGround Truth File doesn't seem to contain data as generated by " 1416 "GridMapNavSimul application.\n Either specify the GT file format " 1418 "visualize_ground_truth to false in the .ini file\n");
1425 gt_timestamps->push_back(timestamp);
1430 atof(curr_tokens[1].c_str()), atof(curr_tokens[2].c_str()),
1431 atof(curr_tokens[3].c_str()));
1432 gt_poses->push_back(curr_pose);
1439 template <
class GRAPH_T>
1441 const std::string& fname_GT, std::vector<mrpt::poses::CPose3D>* gt_poses,
1442 std::vector<mrpt::system::TTimeStamp>* gt_timestamps )
1447 template <
class GRAPH_T>
1449 const std::string& fname_GT, std::vector<mrpt::poses::CPose2D>* gt_poses,
1450 std::vector<mrpt::system::TTimeStamp>* gt_timestamps )
1453 using namespace std;
1461 "\nGround-truth file %s was not found.\n" 1462 "Either specify a valid ground-truth filename or set set the " 1463 "m_visualize_GT flag to false\n",
1469 "\nreadGTFileRGBD_TUM: Couldn't openGT file\n");
1470 ASSERTDEBMSG_(gt_poses,
"No valid std::vector<pose_t>* was given");
1475 for (
size_t i = 0; file_GT.
readLine(curr_line); i++)
1477 if (curr_line.at(0) !=
'#')
1486 vector<string> curr_tokens;
1491 curr_tokens.size() == 8,
1492 "\nGround Truth File doesn't seem to contain data as specified in " 1494 "datasets.\n Either specify correct the GT file format or set " 1495 "visualize_ground_truth to false in the .ini file\n");
1499 quat.
r(atof(curr_tokens[7].c_str()));
1500 quat.x(atof(curr_tokens[4].c_str()));
1501 quat.y(atof(curr_tokens[5].c_str()));
1502 quat.z(atof(curr_tokens[6].c_str()));
1507 curr_coords[0] = atof(curr_tokens[1].c_str());
1508 curr_coords[1] = atof(curr_tokens[2].c_str());
1509 curr_coords[2] = atof(curr_tokens[3].c_str());
1512 pose_t curr_pose(curr_coords[0], curr_coords[1],
y);
1515 pose_diff = curr_pose;
1518 for (; file_GT.
readLine(curr_line);)
1522 curr_tokens.size() == 8,
1523 "\nGround Truth File doesn't seem to contain data as specified in " 1525 "datasets.\n Either specify correct the GT file format or set " 1526 "visualize_ground_truth to false in the .ini file\n");
1533 gt_timestamps->push_back(timestamp);
1537 quat.r(atof(curr_tokens[7].c_str()));
1538 quat.x(atof(curr_tokens[4].c_str()));
1539 quat.y(atof(curr_tokens[5].c_str()));
1540 quat.z(atof(curr_tokens[6].c_str()));
1544 curr_coords[0] = atof(curr_tokens[1].c_str());
1545 curr_coords[1] = atof(curr_tokens[2].c_str());
1546 curr_coords[2] = atof(curr_tokens[3].c_str());
1549 pose_t p(curr_coords[0], curr_coords[1],
y);
1551 p.x() -= pose_diff.x();
1552 p.y() -= pose_diff.y();
1553 p.phi() -= pose_diff.phi();
1555 gt_poses->push_back(
p);
1563 template <
class GRAPH_T>
1567 using namespace std;
1577 const double tmpz[] = {
1578 cos(anglez), -sin(anglez), 0, sin(anglez), cos(anglez), 0, 0, 0, 1};
1584 const double tmpy[] = {cos(angley), 0, sin(angley), 0, 1, 0,
1585 -sin(angley), 0, cos(angley)};
1591 const double tmpx[] = {
1592 1, 0, 0, 0, cos(anglex), -sin(anglex), 0, sin(anglex), cos(anglex)};
1595 stringstream ss_out;
1596 ss_out <<
"\nConstructing the rotation matrix for the GroundTruth Data..." 1598 m_rot_TUM_to_MRPT = rotz * roty * rotx;
1600 ss_out <<
"Rotation matrices for optical=>MRPT transformation" << endl;
1601 ss_out <<
"rotz: " << endl << rotz << endl;
1602 ss_out <<
"roty: " << endl << roty << endl;
1603 ss_out <<
"rotx: " << endl << rotx << endl;
1604 ss_out <<
"Full rotation matrix: " << endl << m_rot_TUM_to_MRPT << endl;
1611 template <
class GRAPH_T>
1618 "\nqueryObserverForEvents method was called even though no Observer " 1619 "object was provided\n");
1621 std::map<std::string, bool> events_occurred;
1622 m_win_observer->returnEventsStruct(&events_occurred);
1623 m_request_to_exit = events_occurred.find(
"Ctrl+c")->second;
1626 if (events_occurred[m_keystroke_odometry])
1628 this->toggleOdometryVisualization();
1631 if (events_occurred[m_keystroke_GT])
1633 this->toggleGTVisualization();
1636 if (events_occurred[m_keystroke_map])
1638 this->toggleMapVisualization();
1641 if (events_occurred[m_keystroke_estimated_trajectory])
1643 this->toggleEstimatedTrajectoryVisualization();
1646 if (events_occurred[m_keystroke_pause_exec])
1648 this->togglePause();
1653 m_node_reg->notifyOfWindowEvents(events_occurred);
1654 m_edge_reg->notifyOfWindowEvents(events_occurred);
1655 m_optimizer->notifyOfWindowEvents(events_occurred);
1660 template <
class GRAPH_T>
1670 if (m_visualize_odometry_poses)
1673 obj->setVisibility(!
obj->isVisible());
1675 obj = scene->getByName(
"robot_odometry_poses");
1676 obj->setVisibility(!
obj->isVisible());
1680 dumpVisibilityErrorMsg(
"visualize_odometry_poses");
1683 m_win->unlockAccess3DScene();
1684 m_win->forceRepaint();
1688 template <
class GRAPH_T>
1701 obj->setVisibility(!
obj->isVisible());
1703 obj = scene->getByName(
"robot_GT");
1704 obj->setVisibility(!
obj->isVisible());
1708 dumpVisibilityErrorMsg(
"visualize_ground_truth");
1711 m_win->unlockAccess3DScene();
1712 m_win->forceRepaint();
1716 template <
class GRAPH_T>
1721 using namespace std;
1730 std::lock_guard<std::mutex> graph_lock(m_graph_section);
1731 num_of_nodes = m_graph.nodeCount();
1735 stringstream scan_name(
"");
1737 for (
int node_cnt = 0; node_cnt != num_of_nodes; ++node_cnt)
1741 scan_name <<
"laser_scan_";
1742 scan_name << node_cnt;
1749 obj->setVisibility(!
obj->isVisible());
1752 m_win->unlockAccess3DScene();
1753 m_win->forceRepaint();
1757 template <
class GRAPH_T>
1767 if (m_visualize_estimated_trajectory)
1770 obj->setVisibility(!
obj->isVisible());
1772 obj = scene->getByName(
"robot_estimated_traj");
1773 obj->setVisibility(!
obj->isVisible());
1777 dumpVisibilityErrorMsg(
"visualize_estimated_trajectory");
1780 m_win->unlockAccess3DScene();
1781 m_win->forceRepaint();
1785 template <
class GRAPH_T>
1792 "Cannot toggle visibility of specified object.\n" 1793 <<
"Make sure that the corresponding visualization flag (" << viz_flag
1794 <<
") is set to true in the .ini file.");
1795 std::this_thread::sleep_for(std::chrono::milliseconds(sleep_time));
1800 template <
class GRAPH_T>
1812 action || observation,
1813 "Neither action or observation contains valid data.");
1818 timestamp = observation->timestamp;
1823 timestamp = action->get(0)->timestamp;
1829 observations->begin();
1830 sens_it != observations->end(); ++sens_it)
1832 timestamp = (*sens_it)->timestamp;
1844 template <
class GRAPH_T>
1852 template <
class GRAPH_T>
1858 map_obj->setName(
"map");
1860 scene->insert(map_obj);
1861 this->m_win->unlockAccess3DScene();
1862 this->m_win->forceRepaint();
1865 template <
class GRAPH_T>
1869 nodes_to_laser_scans2D,
1876 using namespace std;
1887 map_update_timer.
Tic();
1890 std::set<mrpt::graphs::TNodeID> nodes_set;
1897 m_graph.getAllNodes(nodes_set);
1904 nodes_set.insert(m_nodeID_max);
1911 node_it != nodes_set.end(); ++node_it)
1914 stringstream scan_name(
"");
1915 scan_name <<
"laser_scan_";
1916 scan_name << *node_it;
1923 nodes_to_laser_scans2D.find(*node_it);
1926 if (search != nodes_to_laser_scans2D.end() && search->second)
1928 scan_content = search->second;
1931 this->decimateLaserScan(
1932 *scan_content, &scan_decimated,
1943 scan_obj = mrpt::make_aligned_shared<CSetOfObjects>();
1948 m.getAs3DObject(scan_obj);
1950 scan_obj->setName(scan_name.str());
1951 this->setObjectPropsFromNodeID(*node_it, scan_obj);
1959 stringstream prev_scan_name(
"");
1960 prev_scan_name <<
"laser_scan_" << *node_it - 1;
1962 map_obj->getByName(prev_scan_name.str());
1965 scan_obj->setVisibility(prev_obj->isVisible());
1969 map_obj->insert(scan_obj);
1973 scan_obj = std::dynamic_pointer_cast<
CSetOfObjects>(scan_obj);
1978 scan_obj->setPose(scan_pose);
1983 "Laser scans of NodeID " << *node_it <<
"are empty/invalid");
1988 m_win->unlockAccess3DScene();
1989 m_win->forceRepaint();
1991 double elapsed_time = map_update_timer.
Tac();
1993 "updateMapVisualization took: " << elapsed_time <<
"s");
1997 template <
class GRAPH_T>
2003 viz_object->setColor_u8(m_optimized_map_color);
2007 template <
class GRAPH_T>
2011 const int keep_every_n_entries )
2015 size_t scan_size = laser_scan_in.
scan.
size();
2018 std::vector<float> new_scan(
2020 std::vector<char> new_validRange(scan_size);
2021 size_t new_scan_size = 0;
2022 for (
size_t i = 0; i != scan_size; i++)
2024 if (i % keep_every_n_entries == 0)
2026 new_scan[new_scan_size] = laser_scan_in.
scan[i];
2027 new_validRange[new_scan_size] = laser_scan_in.
validRange[i];
2032 new_scan_size, &new_scan[0], &new_validRange[0]);
2037 template <
class GRAPH_T>
2048 "Visualization of data was requested but no CDisplayWindow3D pointer " 2053 GT_cloud->setPointSize(1.0);
2054 GT_cloud->enablePointSmooth();
2055 GT_cloud->enableColorFromX(
false);
2056 GT_cloud->enableColorFromY(
false);
2057 GT_cloud->enableColorFromZ(
false);
2058 GT_cloud->setColor_u8(m_GT_color);
2059 GT_cloud->setName(
"GT_cloud");
2065 m_robot_model_size);
2069 scene->insert(GT_cloud);
2070 scene->insert(robot_model);
2071 m_win->unlockAccess3DScene();
2073 m_win_manager->assignTextMessageParameters(
2076 m_win_manager->addTextMessage(
2077 m_offset_x_left, -m_offset_y_GT,
mrpt::format(
"Ground truth path"),
2081 m_win->forceRepaint();
2086 template <
class GRAPH_T>
2095 if (m_visualize_GT && m_GT_poses_index < m_GT_poses.size())
2099 "Visualization of data was requested but no CDisplayWindow3D " 2100 "pointer was given");
2109 GT_cloud->insertPoint(
p.x(),
p.y(),
p.z());
2112 obj = scene->getByName(
"robot_GT");
2115 robot_obj->setPose(
p);
2116 m_win->unlockAccess3DScene();
2117 m_win->forceRepaint();
2123 template <
class GRAPH_T>
2133 mrpt::make_aligned_shared<CPointCloud>();
2134 odometry_poses_cloud->setPointSize(1.0);
2135 odometry_poses_cloud->enablePointSmooth();
2136 odometry_poses_cloud->enableColorFromX(
false);
2137 odometry_poses_cloud->enableColorFromY(
false);
2138 odometry_poses_cloud->enableColorFromZ(
false);
2139 odometry_poses_cloud->setColor_u8(m_odometry_color);
2140 odometry_poses_cloud->setName(
"odometry_poses_cloud");
2144 "robot_odometry_poses", m_odometry_color, m_robot_model_size);
2148 scene->insert(odometry_poses_cloud);
2149 scene->insert(robot_model);
2150 m_win->unlockAccess3DScene();
2152 m_win_manager->assignTextMessageParameters(
2153 &m_offset_y_odometry,
2154 &m_text_index_odometry);
2155 m_win_manager->addTextMessage(
2156 m_offset_x_left, -m_offset_y_odometry,
mrpt::format(
"Odometry path"),
2158 m_text_index_odometry);
2160 m_win->forceRepaint();
2165 template <
class GRAPH_T>
2172 "Visualization of data was requested but no CDisplayWindow3D pointer " 2184 odometry_poses_cloud->insertPoint(
p.x(),
p.y(),
p.z());
2187 obj = scene->getByName(
"robot_odometry_poses");
2190 robot_obj->setPose(
p);
2192 m_win->unlockAccess3DScene();
2193 m_win->forceRepaint();
2198 template <
class GRAPH_T>
2207 mrpt::make_aligned_shared<CSetOfLines>();
2208 estimated_traj_setoflines->setColor_u8(m_estimated_traj_color);
2209 estimated_traj_setoflines->setLineWidth(1.5);
2210 estimated_traj_setoflines->setName(
"estimated_traj_setoflines");
2213 estimated_traj_setoflines->appendLine(
2220 "robot_estimated_traj", m_estimated_traj_color, m_robot_model_size);
2224 if (m_visualize_estimated_trajectory)
2226 scene->insert(estimated_traj_setoflines);
2228 scene->insert(robot_model);
2229 m_win->unlockAccess3DScene();
2231 if (m_visualize_estimated_trajectory)
2233 m_win_manager->assignTextMessageParameters(
2234 &m_offset_y_estimated_traj,
2235 &m_text_index_estimated_traj);
2236 m_win_manager->addTextMessage(
2237 m_offset_x_left, -m_offset_y_estimated_traj,
2240 m_text_index_estimated_traj);
2243 m_win->forceRepaint();
2248 template <
class GRAPH_T>
2256 std::lock_guard<std::mutex> graph_lock(m_graph_section);
2262 if (m_visualize_estimated_trajectory)
2265 obj = scene->getByName(
"estimated_traj_setoflines");
2271 std::set<mrpt::graphs::TNodeID> nodes_set;
2275 this->getNodeIDsOfEstimatedTrajectory(&nodes_set);
2276 estimated_traj_setoflines->clear();
2278 estimated_traj_setoflines->appendLine(
2284 nodes_set.insert(m_graph.nodeCount() - 1);
2290 it != nodes_set.end(); ++it)
2294 estimated_traj_setoflines->appendLineStrip(
p.x(),
p.y(),
p.z());
2300 obj = scene->getByName(
"robot_estimated_traj");
2303 pose_t curr_estimated_pos = m_graph.nodes[m_graph.nodeCount() - 1];
2304 robot_obj->setPose(curr_estimated_pos);
2306 m_win->unlockAccess3DScene();
2307 m_win->forceRepaint();
2313 template <
class GRAPH_T>
2317 this->setRawlogFile(rawlog_fname);
2318 this->initTRGBDInfoFileParams();
2320 template <
class GRAPH_T>
2323 this->initTRGBDInfoFileParams();
2325 template <
class GRAPH_T>
2330 template <
class GRAPH_T>
2339 info_fname =
dir + name_prefix + rawlog_filename + name_suffix;
2342 template <
class GRAPH_T>
2346 fields[
"Overall number of objects"] =
"";
2347 fields[
"Observations format"] =
"";
2350 template <
class GRAPH_T>
2354 using namespace std;
2360 "\nTRGBDInfoFileParams::parseFile: Couldn't open info file\n");
2363 size_t line_cnt = 0;
2370 if (curr_line.size() == 0)
break;
2374 while (info_file.
readLine(curr_line))
2377 vector<string> curr_tokens;
2388 it != fields.end(); ++it)
2392 it->second = value_part;
2401 template <
class GRAPH_T>
2415 fname =
"output_graph.graph";
2419 "Saving generated graph in VERTEX/EDGE format: " << fname);
2420 m_graph.saveToTextFile(fname);
2425 template <
class GRAPH_T>
2432 "\nsave3DScene was called even though enable_visuals flag is " 2433 "off.\nExiting...\n");
2441 "Could not fetch 3D Scene. Display window must already be closed.");
2452 "Removing CPlanarLaserScan from generated 3DScene...");
2453 scene->removeObject(laser_scan);
2465 fname =
"output_scene.3DScene";
2469 scene->saveToFile(fname);
2471 m_win->unlockAccess3DScene();
2472 m_win->forceRepaint();
2477 template <
class GRAPH_T>
2486 if (m_graph.nodeCount() < 4)
2492 m_nodeID_to_gt_indices[nodeID] = gt_index;
2499 double trans_diff = 0;
2500 double rot_diff = 0;
2502 size_t indices_size = m_nodeID_to_gt_indices.size();
2505 m_curr_deformation_energy = 0;
2511 m_nodeID_to_gt_indices.begin();
2519 pose_t prev_node_pos = m_graph.nodes[prev_it->first];
2520 pose_t prev_gt_pos = m_GT_poses[prev_it->second];
2527 index_it != m_nodeID_to_gt_indices.end(); index_it++)
2529 curr_node_pos = m_graph.nodes[index_it->first];
2530 curr_gt_pos = m_GT_poses[index_it->second];
2532 node_delta_pos = curr_node_pos - prev_node_pos;
2533 gt_delta = curr_gt_pos - prev_gt_pos;
2535 trans_diff = gt_delta.distanceTo(node_delta_pos);
2536 rot_diff = this->accumulateAngleDiffs(gt_delta, node_delta_pos);
2538 m_curr_deformation_energy += (pow(trans_diff, 2) + pow(rot_diff, 2));
2539 m_curr_deformation_energy /= indices_size;
2542 m_deformation_energy_vec.push_back(m_curr_deformation_energy);
2544 prev_node_pos = curr_node_pos;
2545 prev_gt_pos = curr_gt_pos;
2549 "Total deformation energy: " << m_curr_deformation_energy);
2554 template <
class GRAPH_T>
2560 template <
class GRAPH_T>
2574 template <
class GRAPH_T>
2578 using namespace std;
2587 "Evolution of SLAM metric - Deformation Energy (1:1000)", 400, 300);
2589 m_win_plot->setPos(20, 50);
2592 m_win_plot->hold_off();
2593 m_win_plot->enableMousePanZoom(
true);
2598 template <
class GRAPH_T>
2603 ASSERTDEB_(m_win_plot && m_visualize_SLAM_metric);
2606 std::vector<double>
x(m_deformation_energy_vec.size(), 0);
2607 std::vector<double>
y(m_deformation_energy_vec.size(), 0);
2608 for (
size_t i = 0; i !=
x.size(); i++)
2611 y[i] = m_deformation_energy_vec[i] * 1000;
2616 "Deformation Energy (x1000)");
2621 xmax = std::max_element(
x.begin(),
x.end());
2622 ymax = std::max_element(
y.begin(),
y.end());
2625 xmax !=
x.end() ? -(*xmax / 12) : -1,
2626 (xmax !=
x.end() ? *xmax : 1),
2628 (ymax !=
y.end() ? *ymax : 1));
2633 template <
class GRAPH_T>
2638 using namespace std;
2641 stringstream results_ss;
2642 results_ss <<
"Summary: " << std::endl;
2643 results_ss << this->header_sep << std::endl;
2644 results_ss <<
"\tProcessing time: " 2645 << m_time_logger.getMeanTime(
"proc_time") << std::endl;
2647 results_ss <<
"\tDataset Grab time: " << m_dataset_grab_time << std::endl;
2648 results_ss <<
"\tReal-time capable: " 2649 << (m_time_logger.getMeanTime(
"proc_time") < m_dataset_grab_time
2653 results_ss << m_edge_counter.getAsString();
2654 results_ss <<
"\tNum of Nodes: " << m_graph.nodeCount() << std::endl;
2658 std::string config_params = this->getParamsAsString();
2661 const std::string time_res = m_time_logger.getStatsAsText();
2662 const std::string output_res = this->getLogAsString();
2665 report_str->clear();
2667 *report_str += results_ss.str();
2668 *report_str += this->report_sep;
2670 *report_str += config_params;
2671 *report_str += this->report_sep;
2673 *report_str += time_res;
2674 *report_str += this->report_sep;
2676 *report_str += output_res;
2677 *report_str += this->report_sep;
2682 template <
class GRAPH_T>
2684 std::map<std::string, int>* node_stats,
2685 std::map<std::string, int>* edge_stats,
2689 using namespace std;
2692 ASSERTDEBMSG_(node_stats,
"Invalid pointer to node_stats is given");
2693 ASSERTDEBMSG_(edge_stats,
"Invalid pointer to edge_stats is given");
2695 if (m_nodeID_max == 0)
2701 (*node_stats)[
"nodes_total"] = m_nodeID_max + 1;
2705 it != m_edge_counter.cend(); ++it)
2707 (*edge_stats)[it->first] = it->second;
2710 (*edge_stats)[
"loop_closures"] = m_edge_counter.getLoopClosureEdges();
2711 (*edge_stats)[
"edges_total"] = m_edge_counter.getTotalNumOfEdges();
2716 *timestamp = m_curr_timestamp;
2723 template <
class GRAPH_T>
2729 using namespace mrpt;
2734 "Output directory \"%s\" doesn't exist", output_dir_fname.c_str()));
2737 std::lock_guard<std::mutex> graph_lock(m_graph_section);
2745 fname = output_dir_fname +
"/" + m_class_name + ext;
2748 this->initResultsFile(fname);
2749 this->getDescriptiveReport(&report_str);
2750 m_out_streams[fname].printf(
"%s", report_str.c_str());
2753 const std::string time_res = m_time_logger.getStatsAsText();
2754 fname = output_dir_fname +
"/" +
"timings" + ext;
2755 this->initResultsFile(fname);
2756 m_out_streams[fname].printf(
"%s", time_res.c_str());
2760 fname = output_dir_fname +
"/" +
"node_registrar" + ext;
2761 this->initResultsFile(fname);
2762 m_node_reg->getDescriptiveReport(&report_str);
2763 m_out_streams[fname].printf(
"%s", report_str.c_str());
2767 fname = output_dir_fname +
"/" +
"edge_registrar" + ext;
2768 this->initResultsFile(fname);
2769 m_edge_reg->getDescriptiveReport(&report_str);
2770 m_out_streams[fname].printf(
"%s", report_str.c_str());
2774 fname = output_dir_fname +
"/" +
"optimizer" + ext;
2775 this->initResultsFile(fname);
2776 m_optimizer->getDescriptiveReport(&report_str);
2777 m_out_streams[fname].printf(
"%s", report_str.c_str());
2784 "# File includes the evolution of the SLAM metric. Implemented " 2785 "metric computes the \"deformation energy\" that is needed to " 2786 "transfer the estimated trajectory into the ground-truth " 2787 "trajectory (computed as sum of the difference between estimated " 2788 "trajectory and ground truth consecutive poses See \"A comparison " 2789 "of SLAM algorithms based on a graph of relations - W.Burgard et " 2790 "al.\", for more details on the metric.\n");
2792 fname = output_dir_fname +
"/" +
"SLAM_evaluation_metric" + ext;
2793 this->initResultsFile(fname);
2795 m_out_streams[fname].printf(
"%s\n", desc.c_str());
2797 m_deformation_energy_vec.begin();
2798 vec_it != m_deformation_energy_vec.end(); ++vec_it)
2800 m_out_streams[fname].printf(
"%f\n", *vec_it);
2806 template <
class GRAPH_T>
2810 const size_t model_size,
const pose_t& init_pose)
2814 ASSERTDEBMSG_(!model_name.empty(),
"Model name provided is empty.");
2817 this->initRobotModelVisualization();
2818 model->setName(model_name);
2819 model->setColor_u8(model_color);
2820 model->setScale(model_size);
2821 model->setPose(init_pose);
2827 template <
class GRAPH_T>
2829 std::vector<double>* vec_out)
const 2834 *vec_out = m_deformation_energy_vec;
void updateOdometryVisualization()
Update odometry-only cloud with latest odometry estimation.
mrpt::opengl::CSetOfObjects::Ptr setCurrentPositionModel(const std::string &model_name, const mrpt::img::TColor &model_color=mrpt::img::TColor(0, 0, 0), const size_t model_size=1, const pose_t &init_pose=pose_t())
Set the opengl model that indicates the latest position of the trajectory at hand.
double Tac() noexcept
Stops the stopwatch.
typename GRAPH_T::global_pose_t global_pose_t
virtual void getNodeIDsOfEstimatedTrajectory(std::set< mrpt::graphs::TNodeID > *nodes_set) const
Return the list of nodeIDs which make up robot trajectory.
void queryObserverForEvents()
Query the observer instance for any user events.
void updateMapVisualization(const std::map< mrpt::graphs::TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > &nodes_to_laser_scans2D, bool full_update=false)
Update the map visualization based on the current graphSLAM state.
static time_point fromDouble(const double t) noexcept
Create a timestamp from its double representation.
void parseFile()
Parse the RGBD information file to gain information about the rawlog file contents.
void save3DScene(const std::string *fname_in=nullptr) const
Wrapper method around the COpenGLScene::saveToFile method.
VerbosityLevel
Enumeration of available verbosity levels.
std::string read_string(const std::string §ion, const std::string &name, const std::string &defaultValue, bool failIfNotFound=false) const
const_iterator find(const KEY &key) const
A set of object, which are referenced to the coordinates framework established in this object...
void updateGTVisualization()
Display the next ground truth position in the visualization window.
#define THROW_EXCEPTION(msg)
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 toggleMapVisualization()
mrpt::system::TTimeStamp getCurrentTime()
Returns the current (UTC) system time.
void updateSlamMetricVisualization()
Update the displayPlots window with the new information with regards to the metric.
Interface for implementing node registration classes.
double DEG2RAD(const double x)
Degrees to radians.
void initOdometryVisualization()
This class allows loading and storing values and vectors of different types from ".ini" files easily.
bool fileExists(const std::string &fileName)
Test if a given file (or directory) exists.
A high-performance stopwatch, with typical resolution of nanoseconds.
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement, as from a time-of-flight range camera or any other RGBD sensor.
global_pose_t getCurrentRobotPosEstimation() const
Query CGraphSlamEngine instance for the current estimated robot position.
void initRangeImageViewport()
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
mrpt::system::TTimeStamp now()
A shortcut for system::getCurrentTime.
double pitch() const
Get the PITCH angle (in radians)
Interface for implementing edge registration classes.
double yaw() const
Get the YAW angle (in radians)
std::map< std::string, int >::const_iterator const_iterator
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
std::string timeToString(const mrpt::system::TTimeStamp t)
Convert a timestamp into this textual form (UTC): HH:MM:SS.MMMMMM.
virtual void setObjectPropsFromNodeID(const mrpt::graphs::TNodeID nodeID, mrpt::opengl::CSetOfObjects::Ptr &viz_object)
Set the properties of the map visual object based on the nodeID that it was produced by...
std::string fileNameStripInvalidChars(const std::string &filename, const char replacement_to_invalid_chars='_')
Replace invalid filename chars by underscores ('_') or any other user-given char. ...
void initGTVisualization()
GLsizei GLsizei GLuint * obj
#define MRPT_LOG_WARN_STREAM(__CONTENTS)
GLubyte GLubyte GLubyte GLubyte w
void tokenize(const std::string &inString, const std::string &inDelimiters, OUT_CONTAINER &outTokens, bool skipBlankTokens=true) noexcept
Tokenizes a string according to a set of delimiting characters.
mrpt::containers::ContainerReadOnlyProxyAccessor< mrpt::aligned_std_vector< char > > validRange
It's false (=0) on no reflected rays, referenced to elements in scan.
virtual void monitorNodeRegistration(bool registered=false, std::string class_name="Class")
Assert that the given nodes number matches the registered graph nodes, otherwise throw exception...
void loadParams(const std::string &fname)
Read the configuration variables from the .ini file specified by the user.
int read_int(const std::string §ion, const std::string &name, int defaultValue, bool failIfNotFound=false) const
void computeSlamMetric(mrpt::graphs::TNodeID nodeID, size_t gt_index)
Compare the SLAM result (estimated trajectory) with the GT path.
void updateAllVisuals()
Wrapper around the deciders/optimizer updateVisuals methods.
mrpt::Clock::time_point TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
SLAM methods related to graphs of pose constraints.
static double accumulateAngleDiffs(const mrpt::poses::CPose2D &p1, const mrpt::poses::CPose2D &p2)
This base provides a set of functions for maths stuff.
static const std::string report_sep
T r() const
Return r coordinate of the quaternion.
typename GRAPH_T::constraint_t::type_value pose_t
Type of underlying poses (2D/3D).
void alignOpticalWithMRPTFrame()
mrpt::containers::ContainerReadOnlyProxyAccessor< mrpt::aligned_std_vector< float > > scan
The range values of the scan, in meters.
void initTRGBDInfoFileParams()
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.
#define ASSERTDEB_EQUAL_(__A, __B)
static uint64_t getCurrentTime()
std::deque< CObservation::Ptr >::const_iterator const_iterator
You can use CSensoryFrame::begin to get a iterator to the first element.
This namespace contains representation of robot actions and observations.
This object renders a 2D laser scan by means of three elements: the points, the line along end-points...
virtual void updateCurrPosViewport()
Update the viewport responsible for displaying the graph-building procedure in the estimated position...
mrpt::opengl::CSetOfObjects::Ptr initRobotModelVisualizationInternal(const mrpt::poses::CPose2D &p_unused)
Method to help overcome the partial template specialization restriction of C++.
CGraphSlamEngine(const std::string &config_file, const std::string &rawlog_fname="", const std::string &fname_GT="", mrpt::graphslam::CWindowManager *win_manager=NULL, mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_T > *node_reg=NULL, mrpt::graphslam::deciders::CEdgeRegistrationDecider< GRAPH_T > *edge_reg=NULL, mrpt::graphslam::optimizers::CGraphSlamOptimizer< GRAPH_T > *optimizer=NULL)
Constructor of CGraphSlamEngine class template.
void updateEstimatedTrajectoryVisualization(bool full_update=false)
Update the Esstimated robot trajectory with the latest estimated robot position.
#define MRPT_LOG_DEBUG_STREAM(__CONTENTS)
Use: MRPT_LOG_DEBUG_STREAM("Var=" << value << " foo=" << foo_var);
void initEstimatedTrajectoryVisualization()
GLsizei const GLchar ** string
T wrapToPi(T a)
Modifies the given angle to translate it into the ]-pi,pi] range.
void saveGraph(const std::string *fname_in=nullptr) const
Wrapper method around the GRAPH_T::saveToTextFile method.
virtual ~CGraphSlamEngine()
Default Destructor.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
void getDescriptiveReport(std::string *report_str) const
Fill the provided string with a detailed report of the class state.
double roll() const
Get the ROLL angle (in radians)
static const std::string header_sep
Separator string to be used in debugging messages.
CSetOfObjects::Ptr RobotPioneer()
Returns a representation of a Pioneer II mobile base.
virtual mrpt::poses::CPose3D getLSPoseForGridMapVisualization(const mrpt::graphs::TNodeID nodeID) const
return the 3D Pose of a LaserScan that is to be visualized.
void toggleEstimatedTrajectoryVisualization()
void initIntensityImageViewport()
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...
void toggleOdometryVisualization()
virtual bool _execGraphSlamStep(mrpt::obs::CActionCollection::Ptr &action, mrpt::obs::CSensoryFrame::Ptr &observations, mrpt::obs::CObservation::Ptr &observation, size_t &rawlog_entry)
Main class method responsible for parsing each measurement and for executing graphSLAM.
mrpt::opengl::CSetOfObjects::Ptr initRobotModelVisualization()
#define MRPT_LOG_INFO_STREAM(__CONTENTS)
#define ASSERTDEBMSG_(f, __ERROR_MSG)
void initMapVisualization()
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.
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
static void readGTFile(const std::string &fname_GT, std::vector< mrpt::poses::CPose2D > *gt_poses, std::vector< mrpt::system::TTimeStamp > *gt_timestamps=NULL)
Parse the ground truth .txt file and fill in the corresponding gt_poses vector.
virtual GRAPH_T::global_poses_t getRobotEstimatedTrajectory() const
GLdouble GLdouble GLdouble r
static mrpt::system::TTimeStamp getTimeStamp(const mrpt::obs::CActionCollection::Ptr action, const mrpt::obs::CSensoryFrame::Ptr observations, const mrpt::obs::CObservation::Ptr observation)
Fill the TTimestamp in a consistent manner.
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
std::string dateTimeToString(const mrpt::system::TTimeStamp t)
Convert a timestamp into this textual form (UTC time): YEAR/MONTH/DAY,HH:MM:SS.MMM.
void setRawlogFile(const std::string &rawlog_fname)
#define ASSERTDEB_(f)
Defines an assertion mechanism - only when compiled in debug.
bool read_bool(const std::string §ion, const std::string &name, bool defaultValue, bool failIfNotFound=false) const
CSetOfObjects::Ptr CornerXYZ(float scale=1.0)
Returns three arrows representing a X,Y,Z 3D corner.
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
const double & phi() const
Get the phi angle of the 2D pose (in radians)
#define IS_CLASS(ptrObj, class_name)
Evaluates to true if the given pointer to an object (derived from mrpt::rtti::CObject) is of the give...
A RGB color - floats in the range [0,1].
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.
A matrix of dynamic size.
uint64_t TNodeID
A generic numeric type for unique IDs of nodes or entities.
typename GRAPH_T::constraint_t constraint_t
Type of graph constraints.
void loadFromVectors(size_t nRays, const float *scanRanges, const char *scanValidity)
void getMap(mrpt::maps::COccupancyGridMap2D::Ptr map, mrpt::system::TTimeStamp *acquisition_time=NULL) const
std::string trim(const std::string &str)
Removes leading and trailing spaces.
bool execGraphSlamStep(mrpt::obs::CObservation::Ptr &observation, size_t &rawlog_entry)
Wrapper method around _execGraphSlamStep.
Classes for creating GUI windows for 2D and 3D visualization.
void toggleGTVisualization()
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.
bool directoryExists(const std::string &fileName)
Test if a given directory exists (it fails if the given path refers to an existing file)...
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...
An observation of the current (cumulative) odometry for a wheeled robot.
A quaternion, which can represent a 3D rotation as pair , with a real part "r" and a 3D vector ...
void Tic() noexcept
Starts the stopwatch.
std::string extractFileName(const std::string &filePath)
Extract just the name (without extension) of a filename from a complete path plus name plus extension...
#define ASSERT_FILE_EXISTS_(FIL)
A set of independent lines (or segments), one line with its own start and end positions (X...
#define MRPT_LOG_ERROR_STREAM(__CONTENTS)
bool strCmpI(const std::string &s1, const std::string &s2)
Return true if the two strings are equal (case insensitive)
void initCurrPosViewport()
bool insertObservation(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose=NULL)
Insert the observation information into this map.
static void setImagesPathBase(const std::string &path)
const Scalar * const_iterator
Internal auxiliary classes.
void dumpVisibilityErrorMsg(std::string viz_flag, int sleep_time=500)
Wrapper method that used for printing error messages in a consistent manner.
void initSlamMetricVisualization()
#define INVALID_TIMESTAMP
Represents an invalid timestamp, where applicable.
std::string extractFileDirectory(const std::string &filePath)
Extract the whole path (the directory) of a filename from a complete path plus name plus extension...
void updateRangeImageViewport()
In RGB-D TUM Datasets update the Range image displayed in a seperate viewport.
Class acts as a container for storing pointers to mrpt::gui::CDisplayWindow3D, mrpt::graphslam::CWind...
void generateReportFiles(const std::string &output_dir_fname_in)
Generate and write to a corresponding report for each of the respective self/decider/optimizer classe...
A class for storing images as grayscale or RGB bitmaps.
A cloud of points, all with the same color or each depending on its value along a particular coordina...
void initResultsFile(const std::string &fname)
Automate the creation and initialization of a results file relevant to the application.
void initClass()
General initialization method to call from the Class Constructors.
static const std::string & getImagesPathBase()
By default, ".".