22 template <
class GRAPH_T>
24 template <
class GRAPH_T>
27 template <
class GRAPH_T>
34 : m_node_reg(node_reg),
36 m_optimizer(optimizer),
37 m_enable_visuals(win_manager != nullptr),
38 m_config_fname(config_file),
39 m_rawlog_fname(rawlog_fname),
42 m_win_manager(win_manager),
43 m_paused_message(
"Program is paused. Press \"p/P\" to resume."),
44 m_text_index_paused_message(345),
45 m_odometry_color(0, 0, 255),
46 m_GT_color(0, 255, 0),
47 m_estimated_traj_color(255, 165, 0),
48 m_optimized_map_color(255, 0, 0),
49 m_current_constraint_type_color(255, 255, 255),
50 m_robot_model_size(1),
51 m_class_name(
"CGraphSlamEngine"),
52 m_is_first_time_node_reg(true)
57 template <
class GRAPH_T>
68 template <
class GRAPH_T>
69 typename GRAPH_T::global_pose_t
72 std::lock_guard<std::mutex> graph_lock(m_graph_section);
73 return m_node_reg->getCurrentRobotPosEstimation();
76 template <
class GRAPH_T>
77 typename GRAPH_T::global_poses_t
80 std::lock_guard<std::mutex> graph_lock(m_graph_section);
84 template <
class GRAPH_T>
86 std::set<mrpt::graphs::TNodeID>* nodes_set)
const 89 m_graph.getAllNodes(*nodes_set);
92 template <
class GRAPH_T>
101 m_time_logger.setName(m_class_name);
102 this->logging_enable_keep_record =
true;
103 this->setLoggerName(m_class_name);
115 m_supported_constraint_types.push_back(
"CPosePDFGaussianInf");
116 m_supported_constraint_types.push_back(
"CPose3DPDFGaussianInf");
119 const string c_str(
c.GetRuntimeClass()->className);
123 m_supported_constraint_types.begin(),
124 m_supported_constraint_types.end(),
125 c_str) != m_supported_constraint_types.end());
134 "Given graph class " << c_str
135 <<
" has not been tested consistently yet." 136 <<
"Proceed at your own risk.");
141 m_current_constraint_type = c_str;
142 m_current_constraint_type =
"Constraints: " + m_current_constraint_type;
146 if (m_enable_visuals)
148 m_win = m_win_manager->win;
149 m_win_observer = m_win_manager->observer;
154 m_win_observer =
nullptr;
163 m_observation_only_dataset =
false;
164 m_request_to_exit =
false;
170 m_GT_poses_index = 0;
174 m_node_reg->setGraphPtr(&m_graph);
175 m_edge_reg->setGraphPtr(&m_graph);
176 m_optimizer->setGraphPtr(&m_graph);
180 if (m_enable_visuals)
182 m_node_reg->setWindowManagerPtr(m_win_manager);
183 m_edge_reg->setWindowManagerPtr(m_win_manager);
184 m_optimizer->setWindowManagerPtr(m_win_manager);
185 m_edge_counter.setWindowManagerPtr(m_win_manager);
189 m_node_reg->setCriticalSectionPtr(&m_graph_section);
190 m_edge_reg->setCriticalSectionPtr(&m_graph_section);
191 m_optimizer->setCriticalSectionPtr(&m_graph_section);
195 this->loadParams(m_config_fname);
197 if (!m_enable_visuals)
200 m_visualize_odometry_poses = 0;
203 m_visualize_estimated_trajectory = 0;
204 m_visualize_SLAM_metric = 0;
205 m_enable_curr_pos_viewport = 0;
206 m_enable_range_viewport = 0;
207 m_enable_intensity_viewport = 0;
210 m_use_GT = !m_fname_GT.empty();
216 this->alignOpticalWithMRPTFrame();
221 this->readGTFile(m_fname_GT, &m_GT_poses);
229 "Ground truth file was not provided. Switching the related " 230 "visualization parameters off...");
232 m_visualize_SLAM_metric = 0;
236 if (m_enable_visuals)
238 m_win_manager->assignTextMessageParameters(
239 &m_offset_y_timestamp, &m_text_index_timestamp);
244 this->initMapVisualization();
249 if (m_enable_visuals)
252 if (m_visualize_odometry_poses)
254 this->initOdometryVisualization();
259 this->initGTVisualization();
262 this->initEstimatedTrajectoryVisualization();
264 if (m_enable_curr_pos_viewport)
266 this->initCurrPosViewport();
279 m_img_external_storage_dir =
280 rawlog_dir + rawlog_fname_noext +
"_Images/";
287 if (m_enable_range_viewport)
289 this->initRangeImageViewport();
291 if (m_enable_intensity_viewport)
293 this->initIntensityImageViewport();
297 if (m_enable_visuals)
302 obj->setFrequency(5);
303 obj->enableTickMarks();
304 obj->setAxisLimits(-10, -10, -10, 10, 10, 10);
305 obj->setName(
"axis");
308 m_win->unlockAccess3DScene();
309 m_win->forceRepaint();
313 if (m_enable_visuals)
316 m_keystroke_pause_exec =
"p";
317 m_keystroke_odometry =
"o";
318 m_keystroke_GT =
"g";
319 m_keystroke_estimated_trajectory =
"t";
320 m_keystroke_map =
"m";
323 m_win_observer->registerKeystroke(
324 m_keystroke_pause_exec,
"Pause/Resume program execution");
325 m_win_observer->registerKeystroke(
326 m_keystroke_odometry,
"Toggle Odometry visualization");
327 m_win_observer->registerKeystroke(
328 m_keystroke_GT,
"Toggle Ground-Truth visualization");
329 m_win_observer->registerKeystroke(
330 m_keystroke_estimated_trajectory,
331 "Toggle Estimated trajectory visualization");
332 m_win_observer->registerKeystroke(
333 m_keystroke_map,
"Toggle Map visualization");
337 vector<string> vec_edge_types;
338 vec_edge_types.emplace_back(
"Odometry");
339 vec_edge_types.emplace_back(
"ICP2D");
340 vec_edge_types.emplace_back(
"ICP3D");
342 for (
auto cit = vec_edge_types.begin(); cit != vec_edge_types.end(); ++cit)
344 m_edge_counter.addEdgeType(*cit);
348 if (m_enable_visuals)
351 double offset_y_total_edges, offset_y_loop_closures;
352 int text_index_total_edges, text_index_loop_closures;
354 m_win_manager->assignTextMessageParameters(
355 &offset_y_total_edges, &text_index_total_edges);
358 map<string, double> name_to_offset_y;
359 map<string, int> name_to_text_index;
360 for (
auto it = vec_edge_types.begin(); it != vec_edge_types.end(); ++it)
362 m_win_manager->assignTextMessageParameters(
363 &name_to_offset_y[*it], &name_to_text_index[*it]);
366 m_win_manager->assignTextMessageParameters(
367 &offset_y_loop_closures, &text_index_loop_closures);
370 m_edge_counter.setTextMessageParams(
371 name_to_offset_y, name_to_text_index, offset_y_total_edges,
372 text_index_total_edges, offset_y_loop_closures,
373 text_index_loop_closures);
377 if (m_enable_visuals)
379 m_win_manager->assignTextMessageParameters(
380 &m_offset_y_current_constraint_type,
381 &m_text_index_current_constraint_type);
382 m_win_manager->addTextMessage(
383 m_offset_x_left, -m_offset_y_current_constraint_type,
384 m_current_constraint_type,
386 m_text_index_current_constraint_type);
390 if (m_enable_visuals)
392 std::lock_guard<std::mutex> graph_lock(m_graph_section);
393 m_time_logger.enter(
"Visuals");
394 m_node_reg->initializeVisuals();
395 m_edge_reg->initializeVisuals();
396 m_optimizer->initializeVisuals();
397 m_time_logger.leave(
"Visuals");
416 gridmap->insertionOptions.maxOccupancyUpdateCertainty = 0.8f;
417 gridmap->insertionOptions.maxDistanceInsertion = 5;
418 gridmap->insertionOptions.wideningBeamsWithDistance =
true;
419 gridmap->insertionOptions.decimation = 2;
421 m_gridmap_cached = gridmap;
422 m_map_is_cached =
false;
431 octomap->insertionOptions.setOccupancyThres(0.5);
432 octomap->insertionOptions.setProbHit(0.7);
433 octomap->insertionOptions.setProbMiss(0.4);
434 octomap->insertionOptions.setClampingThresMin(0.1192);
435 octomap->insertionOptions.setClampingThresMax(0.971);
438 m_map_is_cached =
false;
445 m_info_params.setRawlogFile(m_rawlog_fname);
446 m_info_params.parseFile();
448 int num_of_objects = std::atoi(
449 m_info_params.fields[
"Overall number of objects"].c_str());
450 m_GT_poses_step = m_GT_poses.size() / num_of_objects;
453 "Overall number of objects in rawlog: " << num_of_objects);
455 "Setting the Ground truth read step to: " << m_GT_poses_step);
457 catch (
const std::exception& e)
463 m_curr_deformation_energy = 0;
464 if (m_visualize_SLAM_metric)
466 this->initSlamMetricVisualization();
470 if (m_enable_visuals)
472 this->m_win->addTextMessage(
474 m_text_index_paused_message);
480 template <
class GRAPH_T>
489 return this->_execGraphSlamStep(
490 action, observations, observation, rawlog_entry);
493 template <
class GRAPH_T>
502 using namespace mrpt;
509 m_time_logger.enter(
"proc_time");
513 format(
"\nConfig file is not read yet.\nExiting... \n"));
519 m_init_timestamp = getTimeStamp(action, observations, observation);
525 m_observation_only_dataset =
true;
531 m_observation_only_dataset =
false;
534 action->getFirstMovementEstimationMean(increment_pose_3d);
535 pose_t increment_pose(increment_pose_3d);
536 m_curr_odometry_only_pose += increment_pose;
544 bool registered_new_node;
546 std::lock_guard<std::mutex> graph_lock(m_graph_section);
547 m_time_logger.enter(
"node_registrar");
548 registered_new_node =
549 m_node_reg->updateState(action, observations, observation);
550 m_time_logger.leave(
"node_registrar");
555 getObservation<CObservation2DRangeScan>(observations, observation);
558 m_last_laser_scan2D = scan;
560 if (!m_first_laser_scan2D)
562 m_first_laser_scan2D = m_last_laser_scan2D;
567 if (registered_new_node)
571 if (m_is_first_time_node_reg)
573 std::lock_guard<std::mutex> graph_lock(m_graph_section);
575 if (m_graph.nodeCount() != 2)
578 "Expected [2] new registered nodes" 579 <<
" but got [" << m_graph.nodeCount() <<
"]");
583 m_nodes_to_laser_scans2D.insert(
584 make_pair(m_nodeID_max, m_first_laser_scan2D));
586 m_is_first_time_node_reg =
false;
593 m_edge_counter.addEdge(
"Odometry");
595 this->monitorNodeRegistration(
596 registered_new_node,
"NodeRegistrationDecider");
602 std::lock_guard<std::mutex> graph_lock(m_graph_section);
604 m_time_logger.enter(
"edge_registrar");
605 m_edge_reg->updateState(action, observations, observation);
606 m_time_logger.leave(
"edge_registrar");
608 this->monitorNodeRegistration(
609 registered_new_node,
"EdgeRegistrationDecider");
612 std::lock_guard<std::mutex> graph_lock(m_graph_section);
614 m_time_logger.enter(
"optimizer");
615 m_optimizer->updateState(action, observations, observation);
616 m_time_logger.leave(
"optimizer");
618 this->monitorNodeRegistration(registered_new_node,
"GraphSlamOptimizer");
621 m_curr_timestamp = getTimeStamp(action, observations, observation);
634 m_curr_odometry_only_pose =
pose_t(obs_odometry->odometry);
635 m_odometry_poses.push_back(m_curr_odometry_only_pose);
639 m_last_laser_scan3D =
652 action->getFirstMovementEstimationMean(increment_pose_3d);
653 pose_t increment_pose(increment_pose_3d);
654 m_curr_odometry_only_pose += increment_pose;
655 m_odometry_poses.push_back(m_curr_odometry_only_pose);
658 if (registered_new_node)
660 this->execDijkstraNodesEstimation();
663 m_nodes_to_laser_scans2D[m_nodeID_max] = m_last_laser_scan2D;
665 if (m_enable_visuals && m_visualize_map)
667 std::lock_guard<std::mutex> graph_lock(m_graph_section);
669 bool full_update =
true;
670 this->updateMapVisualization(m_nodes_to_laser_scans2D, full_update);
674 if (m_enable_visuals)
676 this->updateAllVisuals();
680 std::map<std::string, int> edge_types_to_nums;
681 m_edge_reg->getEdgesStats(&edge_types_to_nums);
682 if (edge_types_to_nums.size())
684 for (
auto it = edge_types_to_nums.begin();
685 it != edge_types_to_nums.end(); ++it)
690 m_edge_counter.setLoopClosureEdgesManually(it->second);
694 m_edge_counter.setEdgesManually(it->first, it->second);
701 if (m_enable_curr_pos_viewport)
703 updateCurrPosViewport();
706 if (m_enable_visuals)
708 bool full_update =
true;
709 m_time_logger.enter(
"Visuals");
710 this->updateEstimatedTrajectoryVisualization(full_update);
711 m_time_logger.leave(
"Visuals");
718 m_time_logger.enter(
"SLAM_metric");
719 this->computeSlamMetric(m_nodeID_max, m_GT_poses_index);
720 m_time_logger.leave(
"SLAM_metric");
721 if (m_visualize_SLAM_metric)
723 m_time_logger.enter(
"Visuals");
724 this->updateSlamMetricVisualization();
725 m_time_logger.leave(
"Visuals");
730 m_map_is_cached =
false;
737 m_time_logger.enter(
"Visuals");
741 if (m_enable_visuals)
745 m_win_manager->addTextMessage(
746 m_offset_x_left, -m_offset_y_timestamp,
748 "Simulated time: %s",
751 m_text_index_timestamp);
755 m_win_manager->addTextMessage(
756 m_offset_x_left, -m_offset_y_timestamp,
761 m_text_index_timestamp);
766 if (m_visualize_odometry_poses && m_odometry_poses.size())
768 this->updateOdometryVisualization();
777 if (m_enable_visuals)
779 this->updateGTVisualization();
782 m_GT_poses_index += m_GT_poses_step;
786 if (m_observation_only_dataset)
788 if (rawlog_entry % 2 == 0)
790 if (m_enable_visuals)
792 this->updateGTVisualization();
795 m_GT_poses_index += m_GT_poses_step;
802 if (m_enable_visuals)
804 this->updateGTVisualization();
807 m_GT_poses_index += m_GT_poses_step;
815 if (m_enable_range_viewport && m_last_laser_scan3D)
817 this->updateRangeImageViewport();
820 if (m_enable_intensity_viewport && m_last_laser_scan3D)
822 this->updateIntensityImageViewport();
827 if (m_enable_visuals)
829 this->queryObserverForEvents();
831 m_time_logger.leave(
"Visuals");
833 m_dataset_grab_time =
835 m_time_logger.leave(
"proc_time");
837 return !m_request_to_exit;
841 template <
class GRAPH_T>
845 std::lock_guard<std::mutex> graph_lock(m_graph_section);
846 m_time_logger.enter(
"dijkstra_nodes_estimation");
847 m_graph.dijkstra_nodes_estimate();
848 m_time_logger.leave(
"dijkstra_nodes_estimation");
852 template <
class GRAPH_T>
857 using namespace mrpt;
859 std::lock_guard<std::mutex> graph_lock(m_graph_section);
860 size_t listed_nodeCount =
866 listed_nodeCount == m_graph.nodeCount(),
868 "listed_nodeCount [%lu] != nodeCount() [%lu]",
869 static_cast<unsigned long>(listed_nodeCount),
870 static_cast<unsigned long>(m_graph.nodeCount())));
874 if (listed_nodeCount != m_graph.nodeCount())
877 class_name <<
" illegally added new nodes to the graph " 878 <<
", wanted to see [" << listed_nodeCount
879 <<
"] but saw [" << m_graph.nodeCount() <<
"]");
881 format(
"Illegal node registration by %s.", class_name.c_str()));
887 template <
class GRAPH_T>
900 if (!m_map_is_cached)
904 map->copyMapContentFrom(*m_gridmap_cached);
907 if (acquisition_time)
909 *acquisition_time = m_map_acq_time;
914 template <
class GRAPH_T>
922 if (!m_map_is_cached)
931 if (acquisition_time)
933 *acquisition_time = m_map_acq_time;
939 template <
class GRAPH_T>
944 using namespace mrpt;
948 std::lock_guard<std::mutex> graph_lock(m_graph_section);
950 if (!constraint_t::is_3D())
958 for (
auto it = m_nodes_to_laser_scans2D.begin();
959 it != m_nodes_to_laser_scans2D.end(); ++it)
968 "LaserScan of nodeID: %lu is not present.",
969 static_cast<unsigned long>(curr_node)));
972 CPose3D scan_pose = getLSPoseForGridMapVisualization(curr_node);
975 gridmap->insertObservation(*curr_laser_scan, &scan_pose);
978 m_map_is_cached =
true;
984 THROW_EXCEPTION(
"Not Implemented Yet. Method is to compute a COctoMap");
991 template <
class GRAPH_T>
998 mrpt::format(
"\nConfiguration file not found: \n%s\n", fname.c_str()));
1004 m_user_decides_about_output_dir = cfg_file.
read_bool(
1005 "GeneralConfiguration",
"user_decides_about_output_dir",
false,
false);
1007 "GeneralConfiguration",
"ground_truth_file_format",
"NavSimul",
false);
1010 int min_verbosity_level =
1011 cfg_file.
read_int(
"GeneralConfiguration",
"class_verbosity", 1,
false);
1018 "VisualizationParameters",
"visualize_map",
true,
false);
1021 m_visualize_odometry_poses = cfg_file.
read_bool(
1022 "VisualizationParameters",
"visualize_odometry_poses",
true,
false);
1023 m_visualize_estimated_trajectory = cfg_file.
read_bool(
1024 "VisualizationParameters",
"visualize_estimated_trajectory",
true,
1029 "VisualizationParameters",
"visualize_ground_truth",
true,
false);
1031 m_visualize_SLAM_metric = cfg_file.
read_bool(
1032 "VisualizationParameters",
"visualize_SLAM_metric",
true,
false);
1035 m_enable_curr_pos_viewport = cfg_file.
read_bool(
1036 "VisualizationParameters",
"enable_curr_pos_viewport",
true,
false);
1037 m_enable_range_viewport = cfg_file.
read_bool(
1038 "VisualizationParameters",
"enable_range_viewport",
false,
false);
1039 m_enable_intensity_viewport = cfg_file.
read_bool(
1040 "VisualizationParameters",
"enable_intensity_viewport",
false,
false);
1042 m_node_reg->loadParams(fname);
1043 m_edge_reg->loadParams(fname);
1044 m_optimizer->loadParams(fname);
1046 m_has_read_config =
true;
1049 template <
class GRAPH_T>
1055 this->getParamsAsString(&str);
1060 template <
class GRAPH_T>
1065 using namespace std;
1067 stringstream ss_out;
1070 <<
"\n------------[ Graphslam_engine Problem Parameters ]------------" 1072 ss_out <<
"Config filename = " << m_config_fname
1075 ss_out <<
"Ground Truth File format = " << m_GT_file_format
1077 ss_out <<
"Ground Truth filename = " << m_fname_GT << std::endl;
1079 ss_out <<
"Visualize odometry = " 1080 << (m_visualize_odometry_poses ?
"TRUE" :
"FALSE") << std::endl;
1081 ss_out <<
"Visualize estimated trajectory = " 1082 << (m_visualize_estimated_trajectory ?
"TRUE" :
"FALSE")
1084 ss_out <<
"Visualize map = " 1085 << (m_visualize_map ?
"TRUE" :
"FALSE") << std::endl;
1086 ss_out <<
"Visualize Ground Truth = " 1087 << (m_visualize_GT ?
"TRUE" :
"FALSE") << std::endl;
1089 ss_out <<
"Visualize SLAM metric plot = " 1090 << (m_visualize_SLAM_metric ?
"TRUE" :
"FALSE") << std::endl;
1092 ss_out <<
"Enable curr. position viewport = " 1093 << (m_enable_curr_pos_viewport ?
"TRUE" :
"FALSE") << endl;
1094 ss_out <<
"Enable range img viewport = " 1095 << (m_enable_range_viewport ?
"TRUE" :
"FALSE") << endl;
1096 ss_out <<
"Enable intensity img viewport = " 1097 << (m_enable_intensity_viewport ?
"TRUE" :
"FALSE") << endl;
1099 ss_out <<
"-----------------------------------------------------------" 1101 ss_out << std::endl;
1104 *params_out = ss_out.str();
1109 template <
class GRAPH_T>
1113 std::cout << getParamsAsString();
1115 m_node_reg->printParams();
1116 m_edge_reg->printParams();
1117 m_optimizer->printParams();
1122 template <
class GRAPH_T>
1126 using namespace std;
1137 m_out_streams[fname].open(fname);
1139 m_out_streams[fname].fileOpenCorrectly(),
1140 mrpt::format(
"\nError while trying to open %s\n", fname.c_str()));
1144 m_out_streams[fname].printf(
"# Mobile Robot Programming Toolkit (MRPT)\n");
1145 m_out_streams[fname].printf(
"# http::/www.mrpt.org\n");
1146 m_out_streams[fname].printf(
"# GraphSlamEngine Application\n");
1147 m_out_streams[fname].printf(
1148 "# Automatically generated file - %s: %s\n", time_spec.c_str(),
1149 cur_date_str.c_str());
1150 m_out_streams[fname].printf(
"%s\n\n", sep.c_str());
1155 template <
class GRAPH_T>
1165 viewp_range = scene->createViewport(
"viewp_range");
1167 m_win_manager->assignViewportParameters(&
x, &
y, &
w, &h);
1168 viewp_range->setViewportPosition(
x,
y, h,
w);
1170 m_win->unlockAccess3DScene();
1171 m_win->forceRepaint();
1176 template <
class GRAPH_T>
1180 std::lock_guard<std::mutex> graph_lock(m_graph_section);
1181 m_time_logger.enter(
"Visuals");
1183 m_node_reg->updateVisuals();
1184 m_edge_reg->updateVisuals();
1185 m_optimizer->updateVisuals();
1187 m_time_logger.leave(
"Visuals");
1191 template <
class GRAPH_T>
1199 if (m_last_laser_scan3D->hasRangeImage)
1207 m_last_laser_scan3D->load();
1209 m_last_laser_scan3D->rangeImage,
false );
1213 viewp_range->setImageView(
img);
1214 m_win->unlockAccess3DScene();
1215 m_win->forceRepaint();
1221 template <
class GRAPH_T>
1231 viewp_intensity = scene->createViewport(
"viewp_intensity");
1233 m_win_manager->assignViewportParameters(&
x, &
y, &
w, &h);
1234 viewp_intensity->setViewportPosition(
x,
y,
w, h);
1236 m_win->unlockAccess3DScene();
1237 m_win->forceRepaint();
1241 template <
class GRAPH_T>
1248 if (m_last_laser_scan3D->hasIntensityImage)
1253 m_last_laser_scan3D->load();
1254 img = m_last_laser_scan3D->intensityImage;
1258 scene->getViewport(
"viewp_intensity");
1259 viewp_intensity->setImageView(
img);
1260 m_win->unlockAccess3DScene();
1261 m_win->forceRepaint();
1267 template <
class GRAPH_T>
1272 return this->initRobotModelVisualizationInternal(
p);
1275 template <
class GRAPH_T>
1284 template <
class GRAPH_T>
1292 template <
class GRAPH_T>
1301 scene->createViewport(
"curr_robot_pose_viewport");
1303 viewp->setCloneView(
"main");
1305 m_win_manager->assignViewportParameters(&
x, &
y, &
w, &h);
1306 viewp->setViewportPosition(
x,
y, h,
w);
1307 viewp->setTransparent(
false);
1308 viewp->getCamera().setAzimuthDegrees(90);
1309 viewp->getCamera().setElevationDegrees(90);
1310 viewp->setCustomBackgroundColor(
1312 viewp->getCamera().setZoomDistance(30);
1313 viewp->getCamera().setOrthogonal();
1315 m_win->unlockAccess3DScene();
1316 m_win->forceRepaint();
1321 template <
class GRAPH_T>
1331 global_pose_t curr_robot_pose = this->getCurrentRobotPosEstimation();
1335 viewp->getCamera().setPointingAt(
CPose3D(curr_robot_pose));
1337 m_win->unlockAccess3DScene();
1338 m_win->forceRepaint();
1344 template <
class GRAPH_T>
1346 const std::string& fname_GT, std::vector<mrpt::poses::CPose2D>* gt_poses,
1347 std::vector<mrpt::system::TTimeStamp>* gt_timestamps)
1350 using namespace std;
1357 "\nGround-truth file %s was not found.\n" 1358 "Either specify a valid ground-truth filename or set set the " 1359 "m_visualize_GT flag to false\n",
1364 ASSERTDEBMSG_(gt_poses,
"\nNo valid std::vector<pose_t>* was given\n");
1369 for (
size_t line_num = 0; file_GT.
readLine(curr_line); line_num++)
1371 vector<string> curr_tokens;
1376 curr_tokens.size() == constraint_t::state_length + 1,
1377 "\nGround Truth File doesn't seem to contain data as generated by " 1379 "GridMapNavSimul application.\n Either specify the GT file format " 1381 "visualize_ground_truth to false in the .ini file\n");
1388 gt_timestamps->push_back(timestamp);
1393 atof(curr_tokens[1].c_str()), atof(curr_tokens[2].c_str()),
1394 atof(curr_tokens[3].c_str()));
1395 gt_poses->push_back(curr_pose);
1402 template <
class GRAPH_T>
1404 const std::string& fname_GT, std::vector<mrpt::poses::CPose3D>* gt_poses,
1405 std::vector<mrpt::system::TTimeStamp>* gt_timestamps)
1410 template <
class GRAPH_T>
1412 const std::string& fname_GT, std::vector<mrpt::poses::CPose2D>* gt_poses,
1413 std::vector<mrpt::system::TTimeStamp>* gt_timestamps)
1416 using namespace std;
1424 "\nGround-truth file %s was not found.\n" 1425 "Either specify a valid ground-truth filename or set set the " 1426 "m_visualize_GT flag to false\n",
1432 "\nreadGTFileRGBD_TUM: Couldn't openGT file\n");
1433 ASSERTDEBMSG_(gt_poses,
"No valid std::vector<pose_t>* was given");
1438 for (
size_t i = 0; file_GT.
readLine(curr_line); i++)
1440 if (curr_line.at(0) !=
'#')
1449 vector<string> curr_tokens;
1454 curr_tokens.size() == 8,
1455 "\nGround Truth File doesn't seem to contain data as specified in " 1457 "datasets.\n Either specify correct the GT file format or set " 1458 "visualize_ground_truth to false in the .ini file\n");
1462 quat.
r(atof(curr_tokens[7].c_str()));
1463 quat.x(atof(curr_tokens[4].c_str()));
1464 quat.y(atof(curr_tokens[5].c_str()));
1465 quat.z(atof(curr_tokens[6].c_str()));
1470 curr_coords[0] = atof(curr_tokens[1].c_str());
1471 curr_coords[1] = atof(curr_tokens[2].c_str());
1472 curr_coords[2] = atof(curr_tokens[3].c_str());
1475 pose_t curr_pose(curr_coords[0], curr_coords[1],
y);
1478 pose_diff = curr_pose;
1481 for (; file_GT.
readLine(curr_line);)
1485 curr_tokens.size() == 8,
1486 "\nGround Truth File doesn't seem to contain data as specified in " 1488 "datasets.\n Either specify correct the GT file format or set " 1489 "visualize_ground_truth to false in the .ini file\n");
1496 gt_timestamps->push_back(timestamp);
1500 quat.r(atof(curr_tokens[7].c_str()));
1501 quat.x(atof(curr_tokens[4].c_str()));
1502 quat.y(atof(curr_tokens[5].c_str()));
1503 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 gt_pose(curr_coords[0], curr_coords[1],
y);
1514 gt_pose.x() -= pose_diff.x();
1515 gt_pose.y() -= pose_diff.y();
1516 gt_pose.phi() -= pose_diff.phi();
1518 gt_poses->push_back(gt_pose);
1526 template <
class GRAPH_T>
1530 using namespace std;
1540 const double tmpz[] = {
1541 cos(anglez), -sin(anglez), 0, sin(anglez), cos(anglez), 0, 0, 0, 1};
1547 const double tmpy[] = {cos(angley), 0, sin(angley), 0, 1, 0,
1548 -sin(angley), 0, cos(angley)};
1554 const double tmpx[] = {
1555 1, 0, 0, 0, cos(anglex), -sin(anglex), 0, sin(anglex), cos(anglex)};
1558 stringstream ss_out;
1559 ss_out <<
"\nConstructing the rotation matrix for the GroundTruth Data..." 1561 m_rot_TUM_to_MRPT = rotz * roty * rotx;
1563 ss_out <<
"Rotation matrices for optical=>MRPT transformation" << endl;
1564 ss_out <<
"rotz: " << endl << rotz << endl;
1565 ss_out <<
"roty: " << endl << roty << endl;
1566 ss_out <<
"rotx: " << endl << rotx << endl;
1567 ss_out <<
"Full rotation matrix: " << endl << m_rot_TUM_to_MRPT << endl;
1574 template <
class GRAPH_T>
1581 "\nqueryObserverForEvents method was called even though no Observer " 1582 "object was provided\n");
1584 std::map<std::string, bool> events_occurred;
1585 m_win_observer->returnEventsStruct(&events_occurred);
1586 m_request_to_exit = events_occurred.find(
"Ctrl+c")->second;
1589 if (events_occurred[m_keystroke_odometry])
1591 this->toggleOdometryVisualization();
1594 if (events_occurred[m_keystroke_GT])
1596 this->toggleGTVisualization();
1599 if (events_occurred[m_keystroke_map])
1601 this->toggleMapVisualization();
1604 if (events_occurred[m_keystroke_estimated_trajectory])
1606 this->toggleEstimatedTrajectoryVisualization();
1609 if (events_occurred[m_keystroke_pause_exec])
1611 this->togglePause();
1616 m_node_reg->notifyOfWindowEvents(events_occurred);
1617 m_edge_reg->notifyOfWindowEvents(events_occurred);
1618 m_optimizer->notifyOfWindowEvents(events_occurred);
1623 template <
class GRAPH_T>
1633 if (m_visualize_odometry_poses)
1636 obj->setVisibility(!
obj->isVisible());
1638 obj = scene->getByName(
"robot_odometry_poses");
1639 obj->setVisibility(!
obj->isVisible());
1643 dumpVisibilityErrorMsg(
"visualize_odometry_poses");
1646 m_win->unlockAccess3DScene();
1647 m_win->forceRepaint();
1651 template <
class GRAPH_T>
1664 obj->setVisibility(!
obj->isVisible());
1666 obj = scene->getByName(
"robot_GT");
1667 obj->setVisibility(!
obj->isVisible());
1671 dumpVisibilityErrorMsg(
"visualize_ground_truth");
1674 m_win->unlockAccess3DScene();
1675 m_win->forceRepaint();
1679 template <
class GRAPH_T>
1684 using namespace std;
1693 std::lock_guard<std::mutex> graph_lock(m_graph_section);
1694 num_of_nodes = m_graph.nodeCount();
1698 stringstream scan_name(
"");
1700 for (
int node_cnt = 0; node_cnt != num_of_nodes; ++node_cnt)
1704 scan_name <<
"laser_scan_";
1705 scan_name << node_cnt;
1712 obj->setVisibility(!
obj->isVisible());
1715 m_win->unlockAccess3DScene();
1716 m_win->forceRepaint();
1720 template <
class GRAPH_T>
1730 if (m_visualize_estimated_trajectory)
1733 obj->setVisibility(!
obj->isVisible());
1735 obj = scene->getByName(
"robot_estimated_traj");
1736 obj->setVisibility(!
obj->isVisible());
1740 dumpVisibilityErrorMsg(
"visualize_estimated_trajectory");
1743 m_win->unlockAccess3DScene();
1744 m_win->forceRepaint();
1748 template <
class GRAPH_T>
1755 "Cannot toggle visibility of specified object.\n" 1756 <<
"Make sure that the corresponding visualization flag (" << viz_flag
1757 <<
") is set to true in the .ini file.");
1758 std::this_thread::sleep_for(std::chrono::milliseconds(sleep_time));
1763 template <
class GRAPH_T>
1775 action || observation,
1776 "Neither action or observation contains valid data.");
1781 timestamp = observation->timestamp;
1786 timestamp = action->get(0)->timestamp;
1791 for (
auto sens_it = observations->begin();
1792 sens_it != observations->end(); ++sens_it)
1794 timestamp = (*sens_it)->timestamp;
1806 template <
class GRAPH_T>
1814 template <
class GRAPH_T>
1820 map_obj->setName(
"map");
1822 scene->insert(map_obj);
1823 this->m_win->unlockAccess3DScene();
1824 this->m_win->forceRepaint();
1827 template <
class GRAPH_T>
1831 nodes_to_laser_scans2D,
1838 using namespace std;
1849 map_update_timer.
Tic();
1852 std::set<mrpt::graphs::TNodeID> nodes_set;
1859 m_graph.getAllNodes(nodes_set);
1866 nodes_set.insert(m_nodeID_max);
1874 stringstream scan_name(
"");
1875 scan_name <<
"laser_scan_";
1876 scan_name << node_it;
1880 auto search = nodes_to_laser_scans2D.find(node_it);
1883 if (search != nodes_to_laser_scans2D.end() && search->second)
1885 scan_content = search->second;
1888 this->decimateLaserScan(
1889 *scan_content, &scan_decimated,
1900 scan_obj = std::make_shared<CSetOfObjects>();
1905 m.getAs3DObject(scan_obj);
1907 scan_obj->setName(scan_name.str());
1908 this->setObjectPropsFromNodeID(node_it, scan_obj);
1916 stringstream prev_scan_name(
"");
1917 prev_scan_name <<
"laser_scan_" << node_it - 1;
1919 map_obj->getByName(prev_scan_name.str());
1922 scan_obj->setVisibility(prev_obj->isVisible());
1926 map_obj->insert(scan_obj);
1930 scan_obj = std::dynamic_pointer_cast<
CSetOfObjects>(scan_obj);
1935 scan_obj->setPose(scan_pose);
1940 "Laser scans of NodeID " << node_it <<
"are empty/invalid");
1945 m_win->unlockAccess3DScene();
1946 m_win->forceRepaint();
1948 double elapsed_time = map_update_timer.
Tac();
1950 "updateMapVisualization took: " << elapsed_time <<
"s");
1954 template <
class GRAPH_T>
1960 viz_object->setColor_u8(m_optimized_map_color);
1964 template <
class GRAPH_T>
1968 const int keep_every_n_entries )
1972 size_t scan_size = laser_scan_in.
scan.
size();
1975 std::vector<float> new_scan(
1977 std::vector<char> new_validRange(scan_size);
1978 size_t new_scan_size = 0;
1979 for (
size_t i = 0; i != scan_size; i++)
1981 if (i % keep_every_n_entries == 0)
1983 new_scan[new_scan_size] = laser_scan_in.
scan[i];
1984 new_validRange[new_scan_size] = laser_scan_in.
validRange[i];
1989 new_scan_size, &new_scan[0], &new_validRange[0]);
1994 template <
class GRAPH_T>
2005 "Visualization of data was requested but no CDisplayWindow3D pointer " 2010 GT_cloud->setPointSize(1.0);
2011 GT_cloud->enablePointSmooth();
2012 GT_cloud->enableColorFromX(
false);
2013 GT_cloud->enableColorFromY(
false);
2014 GT_cloud->enableColorFromZ(
false);
2015 GT_cloud->setColor_u8(m_GT_color);
2016 GT_cloud->setName(
"GT_cloud");
2020 "robot_GT", m_GT_color, m_robot_model_size);
2024 scene->insert(GT_cloud);
2025 scene->insert(robot_model);
2026 m_win->unlockAccess3DScene();
2028 m_win_manager->assignTextMessageParameters(
2029 &m_offset_y_GT, &m_text_index_GT);
2030 m_win_manager->addTextMessage(
2031 m_offset_x_left, -m_offset_y_GT,
mrpt::format(
"Ground truth path"),
2033 m_win->forceRepaint();
2038 template <
class GRAPH_T>
2047 if (m_visualize_GT && m_GT_poses_index < m_GT_poses.size())
2051 "Visualization of data was requested but no CDisplayWindow3D " 2052 "pointer was given");
2061 GT_cloud->insertPoint(
p.x(),
p.y(),
p.z());
2064 obj = scene->getByName(
"robot_GT");
2067 robot_obj->setPose(
p);
2068 m_win->unlockAccess3DScene();
2069 m_win->forceRepaint();
2075 template <
class GRAPH_T>
2085 odometry_poses_cloud->setPointSize(1.0);
2086 odometry_poses_cloud->enablePointSmooth();
2087 odometry_poses_cloud->enableColorFromX(
false);
2088 odometry_poses_cloud->enableColorFromY(
false);
2089 odometry_poses_cloud->enableColorFromZ(
false);
2090 odometry_poses_cloud->setColor_u8(m_odometry_color);
2091 odometry_poses_cloud->setName(
"odometry_poses_cloud");
2095 "robot_odometry_poses", m_odometry_color, m_robot_model_size);
2099 scene->insert(odometry_poses_cloud);
2100 scene->insert(robot_model);
2101 m_win->unlockAccess3DScene();
2103 m_win_manager->assignTextMessageParameters(
2104 &m_offset_y_odometry, &m_text_index_odometry);
2105 m_win_manager->addTextMessage(
2106 m_offset_x_left, -m_offset_y_odometry,
mrpt::format(
"Odometry path"),
2109 m_win->forceRepaint();
2114 template <
class GRAPH_T>
2121 "Visualization of data was requested but no CDisplayWindow3D pointer " 2133 odometry_poses_cloud->insertPoint(
p.x(),
p.y(),
p.z());
2136 obj = scene->getByName(
"robot_odometry_poses");
2139 robot_obj->setPose(
p);
2141 m_win->unlockAccess3DScene();
2142 m_win->forceRepaint();
2147 template <
class GRAPH_T>
2156 std::make_shared<CSetOfLines>();
2157 estimated_traj_setoflines->setColor_u8(m_estimated_traj_color);
2158 estimated_traj_setoflines->setLineWidth(1.5);
2159 estimated_traj_setoflines->setName(
"estimated_traj_setoflines");
2162 estimated_traj_setoflines->appendLine(
2169 "robot_estimated_traj", m_estimated_traj_color, m_robot_model_size);
2173 if (m_visualize_estimated_trajectory)
2175 scene->insert(estimated_traj_setoflines);
2177 scene->insert(robot_model);
2178 m_win->unlockAccess3DScene();
2180 if (m_visualize_estimated_trajectory)
2182 m_win_manager->assignTextMessageParameters(
2183 &m_offset_y_estimated_traj, &m_text_index_estimated_traj);
2184 m_win_manager->addTextMessage(
2185 m_offset_x_left, -m_offset_y_estimated_traj,
2188 m_text_index_estimated_traj);
2191 m_win->forceRepaint();
2196 template <
class GRAPH_T>
2204 std::lock_guard<std::mutex> graph_lock(m_graph_section);
2210 if (m_visualize_estimated_trajectory)
2213 obj = scene->getByName(
"estimated_traj_setoflines");
2219 std::set<mrpt::graphs::TNodeID> nodes_set;
2223 this->getNodeIDsOfEstimatedTrajectory(&nodes_set);
2224 estimated_traj_setoflines->clear();
2226 estimated_traj_setoflines->appendLine(
2232 nodes_set.insert(m_graph.nodeCount() - 1);
2236 for (
unsigned long it : nodes_set)
2240 estimated_traj_setoflines->appendLineStrip(
p.x(),
p.y(),
p.z());
2246 obj = scene->getByName(
"robot_estimated_traj");
2249 pose_t curr_estimated_pos = m_graph.nodes[m_graph.nodeCount() - 1];
2250 robot_obj->setPose(curr_estimated_pos);
2252 m_win->unlockAccess3DScene();
2253 m_win->forceRepaint();
2257 template <
class GRAPH_T>
2261 this->setRawlogFile(rawlog_fname);
2262 this->initTRGBDInfoFileParams();
2264 template <
class GRAPH_T>
2267 this->initTRGBDInfoFileParams();
2270 template <
class GRAPH_T>
2279 info_fname =
dir + name_prefix + rawlog_filename + name_suffix;
2282 template <
class GRAPH_T>
2286 fields[
"Overall number of objects"] =
"";
2287 fields[
"Observations format"] =
"";
2290 template <
class GRAPH_T>
2294 using namespace std;
2300 "\nTRGBDInfoFileParams::parseFile: Couldn't open info file\n");
2303 size_t line_cnt = 0;
2310 if (curr_line.size() == 0)
break;
2314 while (info_file.
readLine(curr_line))
2317 vector<string> curr_tokens;
2327 for (
auto it = fields.begin(); it != fields.end(); ++it)
2331 it->second = value_part;
2339 template <
class GRAPH_T>
2352 fname =
"output_graph.graph";
2356 "Saving generated graph in VERTEX/EDGE format: " << fname);
2357 m_graph.saveToTextFile(fname);
2362 template <
class GRAPH_T>
2368 "\nsave3DScene was called even though enable_visuals flag is " 2369 "off.\nExiting...\n");
2377 "Could not fetch 3D Scene. Display window must already be closed.");
2388 "Removing CPlanarLaserScan from generated 3DScene...");
2389 scene->removeObject(laser_scan);
2401 fname =
"output_scene.3DScene";
2405 scene->saveToFile(fname);
2407 m_win->unlockAccess3DScene();
2408 m_win->forceRepaint();
2413 template <
class GRAPH_T>
2422 if (m_graph.nodeCount() < 4)
2428 m_nodeID_to_gt_indices[nodeID] = gt_index;
2435 double trans_diff = 0;
2436 double rot_diff = 0;
2438 size_t indices_size = m_nodeID_to_gt_indices.size();
2441 m_curr_deformation_energy = 0;
2444 auto start_it = m_nodeID_to_gt_indices.begin();
2448 auto prev_it = start_it;
2450 pose_t prev_node_pos = m_graph.nodes[prev_it->first];
2451 pose_t prev_gt_pos = m_GT_poses[prev_it->second];
2456 for (
auto index_it = start_it; index_it != m_nodeID_to_gt_indices.end();
2459 curr_node_pos = m_graph.nodes[index_it->first];
2460 curr_gt_pos = m_GT_poses[index_it->second];
2462 node_delta_pos = curr_node_pos - prev_node_pos;
2463 gt_delta = curr_gt_pos - prev_gt_pos;
2465 trans_diff = gt_delta.distanceTo(node_delta_pos);
2466 rot_diff = this->accumulateAngleDiffs(gt_delta, node_delta_pos);
2468 m_curr_deformation_energy += (pow(trans_diff, 2) + pow(rot_diff, 2));
2469 m_curr_deformation_energy /= indices_size;
2472 m_deformation_energy_vec.push_back(m_curr_deformation_energy);
2474 prev_node_pos = curr_node_pos;
2475 prev_gt_pos = curr_gt_pos;
2479 "Total deformation energy: " << m_curr_deformation_energy);
2484 template <
class GRAPH_T>
2490 template <
class GRAPH_T>
2504 template <
class GRAPH_T>
2514 m_win_plot = std::make_unique<mrpt::gui::CDisplayWindowPlots>(
2515 "Evolution of SLAM metric - Deformation Energy (1:1000)", 400, 300);
2517 m_win_plot->setPos(20, 50);
2520 m_win_plot->hold_off();
2521 m_win_plot->enableMousePanZoom(
true);
2526 template <
class GRAPH_T>
2531 ASSERTDEB_(m_win_plot && m_visualize_SLAM_metric);
2534 std::vector<double>
x(m_deformation_energy_vec.size(), 0);
2535 std::vector<double>
y(m_deformation_energy_vec.size(), 0);
2536 for (
size_t i = 0; i !=
x.size(); i++)
2539 y[i] = m_deformation_energy_vec[i] * 1000;
2542 m_win_plot->plot(
x,
y,
"r-1",
"Deformation Energy (x1000)");
2546 std::vector<double>::const_iterator xmax, ymax;
2547 xmax = std::max_element(
x.begin(),
x.end());
2548 ymax = std::max_element(
y.begin(),
y.end());
2551 xmax !=
x.end() ? -(*xmax / 12) : -1,
2552 (xmax !=
x.end() ? *xmax : 1),
2554 (ymax !=
y.end() ? *ymax : 1));
2559 template <
class GRAPH_T>
2564 using namespace std;
2567 stringstream results_ss;
2568 results_ss <<
"Summary: " << std::endl;
2569 results_ss << this->header_sep << std::endl;
2570 results_ss <<
"\tProcessing time: " 2571 << m_time_logger.getMeanTime(
"proc_time") << std::endl;
2573 results_ss <<
"\tDataset Grab time: " << m_dataset_grab_time << std::endl;
2574 results_ss <<
"\tReal-time capable: " 2575 << (m_time_logger.getMeanTime(
"proc_time") < m_dataset_grab_time
2579 results_ss << m_edge_counter.getAsString();
2580 results_ss <<
"\tNum of Nodes: " << m_graph.nodeCount() << std::endl;
2584 std::string config_params = this->getParamsAsString();
2587 const std::string time_res = m_time_logger.getStatsAsText();
2588 const std::string output_res = this->getLogAsString();
2591 report_str->clear();
2593 *report_str += results_ss.str();
2594 *report_str += this->report_sep;
2596 *report_str += config_params;
2597 *report_str += this->report_sep;
2599 *report_str += time_res;
2600 *report_str += this->report_sep;
2602 *report_str += output_res;
2603 *report_str += this->report_sep;
2608 template <
class GRAPH_T>
2610 std::map<std::string, int>* node_stats,
2614 using namespace std;
2617 ASSERTDEBMSG_(node_stats,
"Invalid pointer to node_stats is given");
2618 ASSERTDEBMSG_(edge_stats,
"Invalid pointer to edge_stats is given");
2620 if (m_nodeID_max == 0)
2626 (*node_stats)[
"nodes_total"] = m_nodeID_max + 1;
2629 for (
auto it = m_edge_counter.cbegin(); it != m_edge_counter.cend(); ++it)
2631 (*edge_stats)[it->first] = it->second;
2634 (*edge_stats)[
"loop_closures"] = m_edge_counter.getLoopClosureEdges();
2635 (*edge_stats)[
"edges_total"] = m_edge_counter.getTotalNumOfEdges();
2640 *timestamp = m_curr_timestamp;
2647 template <
class GRAPH_T>
2653 using namespace mrpt;
2658 "Output directory \"%s\" doesn't exist", output_dir_fname.c_str()));
2661 std::lock_guard<std::mutex> graph_lock(m_graph_section);
2669 fname = output_dir_fname +
"/" + m_class_name + ext;
2672 this->initResultsFile(fname);
2673 this->getDescriptiveReport(&report_str);
2674 m_out_streams[fname].printf(
"%s", report_str.c_str());
2677 const std::string time_res = m_time_logger.getStatsAsText();
2678 fname = output_dir_fname +
"/" +
"timings" + ext;
2679 this->initResultsFile(fname);
2680 m_out_streams[fname].printf(
"%s", time_res.c_str());
2684 fname = output_dir_fname +
"/" +
"node_registrar" + ext;
2685 this->initResultsFile(fname);
2686 m_node_reg->getDescriptiveReport(&report_str);
2687 m_out_streams[fname].printf(
"%s", report_str.c_str());
2691 fname = output_dir_fname +
"/" +
"edge_registrar" + ext;
2692 this->initResultsFile(fname);
2693 m_edge_reg->getDescriptiveReport(&report_str);
2694 m_out_streams[fname].printf(
"%s", report_str.c_str());
2698 fname = output_dir_fname +
"/" +
"optimizer" + ext;
2699 this->initResultsFile(fname);
2700 m_optimizer->getDescriptiveReport(&report_str);
2701 m_out_streams[fname].printf(
"%s", report_str.c_str());
2708 "# File includes the evolution of the SLAM metric. Implemented " 2709 "metric computes the \"deformation energy\" that is needed to " 2710 "transfer the estimated trajectory into the ground-truth " 2711 "trajectory (computed as sum of the difference between estimated " 2712 "trajectory and ground truth consecutive poses See \"A comparison " 2713 "of SLAM algorithms based on a graph of relations - W.Burgard et " 2714 "al.\", for more details on the metric.\n");
2716 fname = output_dir_fname +
"/" +
"SLAM_evaluation_metric" + ext;
2717 this->initResultsFile(fname);
2719 m_out_streams[fname].printf(
"%s\n", desc.c_str());
2720 for (
auto vec_it = m_deformation_energy_vec.begin();
2721 vec_it != m_deformation_energy_vec.end(); ++vec_it)
2723 m_out_streams[fname].printf(
"%f\n", *vec_it);
2729 template <
class GRAPH_T>
2733 const size_t model_size,
const pose_t& init_pose)
2736 this->initRobotModelVisualization();
2737 model->setName(model_name);
2738 model->setColor_u8(model_color);
2739 model->setScale(model_size);
2740 model->setPose(init_pose);
2745 template <
class GRAPH_T>
2747 std::vector<double>* vec_out)
const 2749 *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.
CGraphSlamEngine(const std::string &config_file, const std::string &rawlog_fname="", const std::string &fname_GT="", mrpt::graphslam::CWindowManager *win_manager=nullptr, mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_T > *node_reg=nullptr, mrpt::graphslam::deciders::CEdgeRegistrationDecider< GRAPH_T > *edge_reg=nullptr, mrpt::graphslam::optimizers::CGraphSlamOptimizer< GRAPH_T > *optimizer=nullptr)
Constructor of CGraphSlamEngine class template.
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
bool getGraphSlamStats(std::map< std::string, int > *node_stats, std::map< std::string, int > *edge_stats, mrpt::system::TTimeStamp *timestamp=nullptr)
Fill the given maps with stats regarding the overall execution of graphslam.
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)
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
void initRangeImageViewport()
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)
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. ...
static Ptr Create(Args &&... args)
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()
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...
#define IS_CLASS(obj, class_name)
True if the given reference to object (derived from mrpt::rtti::CObject) is of the given class...
mrpt::opengl::CSetOfObjects::Ptr initRobotModelVisualizationInternal(const mrpt::poses::CPose2D &p_unused)
Method to help overcome the partial template specialization restriction of C++.
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.
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...
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.
static Ptr Create(Args &&... args)
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)
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.
static void readGTFileRGBD_TUM(const std::string &fname_GT, std::vector< mrpt::poses::CPose2D > *gt_poses, std::vector< mrpt::system::TTimeStamp > *gt_timestamps=nullptr)
Parse the ground truth .txt file and fill in the corresponding m_GT_poses vector. ...
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)
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.
void toggleGTVisualization()
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)...
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)
static void readGTFile(const std::string &fname_GT, std::vector< mrpt::poses::CPose2D > *gt_poses, std::vector< mrpt::system::TTimeStamp > *gt_timestamps=nullptr)
Parse the ground truth .txt file and fill in the corresponding gt_poses vector.
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()
~CGraphSlamEngine() override
static void setImagesPathBase(const std::string &path)
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...
bool insertObservation(const mrpt::obs::CObservation &obs, const mrpt::poses::CPose3D *robotPose=nullptr)
Insert the observation information into this map.
A class for storing images as grayscale or RGB bitmaps.
void getMap(mrpt::maps::COccupancyGridMap2D::Ptr map, mrpt::system::TTimeStamp *acquisition_time=nullptr) const
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, ".".