10 #ifndef CGRAPHSLAMENGINE_IMPL_H 11 #define CGRAPHSLAMENGINE_IMPL_H 17 template <
class GRAPH_T>
19 template <
class GRAPH_T>
25 template <
class GRAPH_T>
37 : m_node_reg(node_reg),
39 m_optimizer(optimizer),
40 m_enable_visuals(win_manager != nullptr),
41 m_config_fname(config_file),
42 m_rawlog_fname(rawlog_fname),
45 m_win_manager(win_manager),
46 m_paused_message(
"Program is paused. Press \"p/P\" to resume."),
47 m_text_index_paused_message(345),
48 m_odometry_color(0, 0, 255),
49 m_GT_color(0, 255, 0),
50 m_estimated_traj_color(255, 165, 0),
51 m_optimized_map_color(255, 0, 0),
52 m_current_constraint_type_color(255, 255, 255),
53 m_robot_model_size(1),
54 m_class_name(
"CGraphSlamEngine"),
55 m_is_first_time_node_reg(true)
60 template <
class GRAPH_T>
68 "In Destructor: Deleting CGraphSlamEngine instance...");
71 for (
fstreams_out_it it = m_out_streams.begin(); it != m_out_streams.end();
74 if ((it->second)->fileOpenCorrectly())
77 (it->second)->close();
85 CImage::setImagesPathBase(m_img_prev_path_base);
99 template <
class GRAPH_T>
100 typename GRAPH_T::global_pose_t
105 std::lock_guard<std::mutex> m_graph_lock(m_graph_section);
106 return m_node_reg->getCurrentRobotPosEstimation();
111 template <
class GRAPH_T>
113 typename GRAPH_T::global_poses_t* graph_poses)
const 117 std::lock_guard<std::mutex> m_graph_lock(m_graph_section);
118 *graph_poses = m_graph.nodes;
122 template <
class GRAPH_T>
124 std::set<mrpt::utils::TNodeID>* nodes_set)
const 128 m_graph.getAllNodes(*nodes_set);
132 template <
class GRAPH_T>
136 using namespace mrpt;
142 m_time_logger.setName(m_class_name);
143 this->logging_enable_keep_record =
true;
144 this->setLoggerName(m_class_name);
156 m_supported_constraint_types.push_back(
"CPosePDFGaussianInf");
157 m_supported_constraint_types.push_back(
"CPose3DPDFGaussianInf");
160 const string c_str(
c.GetRuntimeClass()->className);
164 m_supported_constraint_types.begin(),
165 m_supported_constraint_types.end(),
166 c_str) != m_supported_constraint_types.end());
175 "Given graph class " << c_str
176 <<
" has not been tested consistently yet." 177 <<
"Proceed at your own risk.");
182 m_current_constraint_type = c_str;
183 m_current_constraint_type =
"Constraints: " + m_current_constraint_type;
187 if (m_enable_visuals)
189 m_win = m_win_manager->win;
190 m_win_observer = m_win_manager->observer;
195 m_win_observer =
nullptr;
203 m_win_plot =
nullptr;
205 m_observation_only_dataset =
false;
206 m_request_to_exit =
false;
212 m_GT_poses_index = 0;
216 m_node_reg->setGraphPtr(&m_graph);
217 m_edge_reg->setGraphPtr(&m_graph);
218 m_optimizer->setGraphPtr(&m_graph);
222 if (m_enable_visuals)
224 m_node_reg->setWindowManagerPtr(m_win_manager);
225 m_edge_reg->setWindowManagerPtr(m_win_manager);
226 m_optimizer->setWindowManagerPtr(m_win_manager);
227 m_edge_counter.setWindowManagerPtr(m_win_manager);
231 m_node_reg->setCriticalSectionPtr(&m_graph_section);
232 m_edge_reg->setCriticalSectionPtr(&m_graph_section);
233 m_optimizer->setCriticalSectionPtr(&m_graph_section);
237 this->loadParams(m_config_fname);
239 if (!m_enable_visuals)
242 m_visualize_odometry_poses = 0;
245 m_visualize_estimated_trajectory = 0;
246 m_visualize_SLAM_metric = 0;
247 m_enable_curr_pos_viewport = 0;
248 m_enable_range_viewport = 0;
249 m_enable_intensity_viewport = 0;
252 m_use_GT = !m_fname_GT.empty();
258 this->alignOpticalWithMRPTFrame();
263 this->readGTFile(m_fname_GT, &m_GT_poses);
271 "Ground truth file was not provided. Switching the related " 272 "visualization parameters off...");
274 m_visualize_SLAM_metric = 0;
278 if (m_enable_visuals)
280 m_win_manager->assignTextMessageParameters(
281 &m_offset_y_timestamp, &m_text_index_timestamp);
286 this->initMapVisualization();
291 if (m_enable_visuals)
294 if (m_visualize_odometry_poses)
296 this->initOdometryVisualization();
301 this->initGTVisualization();
304 this->initEstimatedTrajectoryVisualization();
306 if (m_enable_curr_pos_viewport)
308 this->initCurrPosViewport();
316 m_img_prev_path_base = CImage::getImagesPathBase();
322 rawlog_dir + rawlog_fname_noext +
"_Images/";
323 CImage::setImagesPathBase(m_img_external_storage_dir);
329 if (m_enable_range_viewport)
331 this->initRangeImageViewport();
333 if (m_enable_intensity_viewport)
335 this->initIntensityImageViewport();
339 if (m_enable_visuals)
344 obj->setFrequency(5);
345 obj->enableTickMarks();
346 obj->setAxisLimits(-10, -10, -10, 10, 10, 10);
347 obj->setName(
"axis");
350 m_win->unlockAccess3DScene();
351 m_win->forceRepaint();
355 if (m_enable_visuals)
358 m_keystroke_pause_exec =
"p";
359 m_keystroke_odometry =
"o";
360 m_keystroke_GT =
"g";
361 m_keystroke_estimated_trajectory =
"t";
362 m_keystroke_map =
"m";
365 m_win_observer->registerKeystroke(
366 m_keystroke_pause_exec,
"Pause/Resume program execution");
367 m_win_observer->registerKeystroke(
368 m_keystroke_odometry,
"Toggle Odometry visualization");
369 m_win_observer->registerKeystroke(
370 m_keystroke_GT,
"Toggle Ground-Truth visualization");
371 m_win_observer->registerKeystroke(
372 m_keystroke_estimated_trajectory,
373 "Toggle Estimated trajectory visualization");
374 m_win_observer->registerKeystroke(
375 m_keystroke_map,
"Toggle Map visualization");
379 vector<string> vec_edge_types;
380 vec_edge_types.push_back(
"Odometry");
381 vec_edge_types.push_back(
"ICP2D");
382 vec_edge_types.push_back(
"ICP3D");
385 cit != vec_edge_types.end(); ++cit)
387 m_edge_counter.addEdgeType(*cit);
391 if (m_enable_visuals)
394 double offset_y_total_edges, offset_y_loop_closures;
395 int text_index_total_edges, text_index_loop_closures;
397 m_win_manager->assignTextMessageParameters(
398 &offset_y_total_edges, &text_index_total_edges);
401 map<string, double> name_to_offset_y;
402 map<string, int> name_to_text_index;
404 it != vec_edge_types.end(); ++it)
406 m_win_manager->assignTextMessageParameters(
407 &name_to_offset_y[*it], &name_to_text_index[*it]);
410 m_win_manager->assignTextMessageParameters(
411 &offset_y_loop_closures, &text_index_loop_closures);
414 m_edge_counter.setTextMessageParams(
415 name_to_offset_y, name_to_text_index, offset_y_total_edges,
416 text_index_total_edges, offset_y_loop_closures,
417 text_index_loop_closures);
421 if (m_enable_visuals)
423 m_win_manager->assignTextMessageParameters(
424 &m_offset_y_current_constraint_type,
425 &m_text_index_current_constraint_type);
426 m_win_manager->addTextMessage(
427 m_offset_x_left, -m_offset_y_current_constraint_type,
428 m_current_constraint_type,
TColorf(m_current_constraint_type_color),
429 m_text_index_current_constraint_type);
433 if (m_enable_visuals)
435 std::lock_guard<std::mutex> m_graph_lock(m_graph_section);
436 m_time_logger.enter(
"Visuals");
437 m_node_reg->initializeVisuals();
438 m_edge_reg->initializeVisuals();
439 m_optimizer->initializeVisuals();
440 m_time_logger.leave(
"Visuals");
448 mrpt::make_aligned_shared<mrpt::maps::COccupancyGridMap2D>();
459 gridmap->insertionOptions.maxOccupancyUpdateCertainty = 0.8f;
460 gridmap->insertionOptions.maxDistanceInsertion = 5;
461 gridmap->insertionOptions.wideningBeamsWithDistance =
true;
462 gridmap->insertionOptions.decimation = 2;
464 m_gridmap_cached = gridmap;
465 m_map_is_cached =
false;
471 mrpt::make_aligned_shared<mrpt::maps::COctoMap>();
475 octomap->insertionOptions.setOccupancyThres(0.5);
476 octomap->insertionOptions.setProbHit(0.7);
477 octomap->insertionOptions.setProbMiss(0.4);
478 octomap->insertionOptions.setClampingThresMin(0.1192);
479 octomap->insertionOptions.setClampingThresMax(0.971);
481 m_octomap_cached = octomap;
482 m_map_is_cached =
false;
489 m_info_params.setRawlogFile(m_rawlog_fname);
490 m_info_params.parseFile();
492 int num_of_objects = std::atoi(
493 m_info_params.fields[
"Overall number of objects"].c_str());
494 m_GT_poses_step = m_GT_poses.size() / num_of_objects;
497 "Overall number of objects in rawlog: " << num_of_objects);
499 "Setting the Ground truth read step to: " << m_GT_poses_step);
501 catch (std::exception& e)
507 m_curr_deformation_energy = 0;
508 if (m_visualize_SLAM_metric)
510 this->initSlamMetricVisualization();
514 if (m_enable_visuals)
516 this->m_win->addTextMessage(
518 m_text_index_paused_message);
524 template <
class GRAPH_T>
533 return this->_execGraphSlamStep(
534 action, observations, observation, rawlog_entry);
537 template <
class GRAPH_T>
546 using namespace mrpt;
554 m_time_logger.enter(
"proc_time");
558 format(
"\nConfig file is not read yet.\nExiting... \n"));
564 m_init_timestamp = getTimeStamp(action, observations, observation);
570 m_observation_only_dataset =
true;
577 m_observation_only_dataset =
false;
580 action->getFirstMovementEstimationMean(increment_pose_3d);
581 pose_t increment_pose(increment_pose_3d);
582 m_curr_odometry_only_pose += increment_pose;
590 bool registered_new_node;
592 std::lock_guard<std::mutex> m_graph_lock(m_graph_section);
593 m_time_logger.enter(
"node_registrar");
594 registered_new_node =
595 m_node_reg->updateState(action, observations, observation);
596 m_time_logger.leave(
"node_registrar");
601 getObservation<CObservation2DRangeScan>(observations, observation);
604 m_last_laser_scan2D = scan;
606 if (!m_first_laser_scan2D)
608 m_first_laser_scan2D = m_last_laser_scan2D;
613 if (registered_new_node)
617 if (m_is_first_time_node_reg)
619 std::lock_guard<std::mutex> m_graph_lock(m_graph_section);
621 if (m_graph.nodeCount() != 2)
624 "Expected [2] new registered nodes" 625 <<
" but got [" << m_graph.nodeCount() <<
"]");
628 m_is_first_time_node_reg =
false;
630 m_nodes_to_laser_scans2D.insert(
631 make_pair(m_nodeID_max, m_first_laser_scan2D));
638 m_edge_counter.addEdge(
"Odometry");
640 this->monitorNodeRegistration(
641 registered_new_node,
"NodeRegistrationDecider");
647 std::lock_guard<std::mutex> m_graph_lock(m_graph_section);
649 m_time_logger.enter(
"edge_registrar");
650 m_edge_reg->updateState(action, observations, observation);
651 m_time_logger.leave(
"edge_registrar");
653 this->monitorNodeRegistration(
654 registered_new_node,
"EdgeRegistrationDecider");
657 std::lock_guard<std::mutex> m_graph_lock(m_graph_section);
659 m_time_logger.enter(
"optimizer");
660 m_optimizer->updateState(action, observations, observation);
661 m_time_logger.leave(
"optimizer");
663 this->monitorNodeRegistration(registered_new_node,
"GraphSlamOptimizer");
666 m_curr_timestamp = getTimeStamp(action, observations, observation);
679 m_curr_odometry_only_pose =
pose_t(obs_odometry->odometry);
680 m_odometry_poses.push_back(m_curr_odometry_only_pose);
684 m_last_laser_scan3D =
697 action->getFirstMovementEstimationMean(increment_pose_3d);
698 pose_t increment_pose(increment_pose_3d);
699 m_curr_odometry_only_pose += increment_pose;
700 m_odometry_poses.push_back(m_curr_odometry_only_pose);
703 if (registered_new_node)
705 this->execDijkstraNodesEstimation();
708 m_nodes_to_laser_scans2D[m_nodeID_max] = m_last_laser_scan2D;
710 if (m_enable_visuals && m_visualize_map)
712 std::lock_guard<std::mutex> m_graph_lock(m_graph_section);
714 bool full_update =
true;
715 this->updateMapVisualization(m_nodes_to_laser_scans2D, full_update);
719 if (m_enable_visuals)
721 this->updateAllVisuals();
725 std::map<std::string, int> edge_types_to_nums;
726 m_edge_reg->getEdgesStats(&edge_types_to_nums);
727 if (edge_types_to_nums.size())
730 edge_types_to_nums.begin();
731 it != edge_types_to_nums.end(); ++it)
736 m_edge_counter.setLoopClosureEdgesManually(it->second);
740 m_edge_counter.setEdgesManually(it->first, it->second);
747 if (m_enable_curr_pos_viewport)
749 updateCurrPosViewport();
752 if (m_enable_visuals)
754 bool full_update =
true;
755 m_time_logger.enter(
"Visuals");
756 this->updateEstimatedTrajectoryVisualization(full_update);
757 m_time_logger.leave(
"Visuals");
764 m_time_logger.enter(
"SLAM_metric");
765 this->computeSlamMetric(m_nodeID_max, m_GT_poses_index);
766 m_time_logger.leave(
"SLAM_metric");
767 if (m_visualize_SLAM_metric)
769 m_time_logger.enter(
"Visuals");
770 this->updateSlamMetricVisualization();
771 m_time_logger.leave(
"Visuals");
776 m_map_is_cached =
false;
783 m_time_logger.enter(
"Visuals");
787 if (m_enable_visuals)
791 m_win_manager->addTextMessage(
792 m_offset_x_left, -m_offset_y_timestamp,
794 "Simulated time: %s",
797 m_text_index_timestamp);
801 m_win_manager->addTextMessage(
802 m_offset_x_left, -m_offset_y_timestamp,
807 m_text_index_timestamp);
812 if (m_visualize_odometry_poses && m_odometry_poses.size())
814 this->updateOdometryVisualization();
823 if (m_enable_visuals)
825 this->updateGTVisualization();
828 m_GT_poses_index += m_GT_poses_step;
832 if (m_observation_only_dataset)
834 if (rawlog_entry % 2 == 0)
836 if (m_enable_visuals)
838 this->updateGTVisualization();
841 m_GT_poses_index += m_GT_poses_step;
848 if (m_enable_visuals)
850 this->updateGTVisualization();
853 m_GT_poses_index += m_GT_poses_step;
861 if (m_enable_range_viewport && m_last_laser_scan3D)
863 this->updateRangeImageViewport();
866 if (m_enable_intensity_viewport && m_last_laser_scan3D)
868 this->updateIntensityImageViewport();
873 if (m_enable_visuals)
875 this->queryObserverForEvents();
877 m_time_logger.leave(
"Visuals");
879 m_dataset_grab_time =
881 m_time_logger.leave(
"proc_time");
883 return !m_request_to_exit;
887 template <
class GRAPH_T>
891 std::lock_guard<std::mutex> m_graph_lock(m_graph_section);
892 m_time_logger.enter(
"dijkstra_nodes_estimation");
893 m_graph.dijkstra_nodes_estimate();
894 m_time_logger.leave(
"dijkstra_nodes_estimation");
898 template <
class GRAPH_T>
904 using namespace mrpt;
906 std::lock_guard<std::mutex> m_graph_lock(m_graph_section);
907 size_t listed_nodeCount =
913 listed_nodeCount == m_graph.nodeCount(),
915 "listed_nodeCount [%lu] != nodeCount() [%lu]",
916 static_cast<unsigned long>(listed_nodeCount),
917 static_cast<unsigned long>(m_graph.nodeCount())));
921 if (listed_nodeCount != m_graph.nodeCount())
924 class_name <<
" illegally added new nodes to the graph " 925 <<
", wanted to see [" << listed_nodeCount
926 <<
"] but saw [" << m_graph.nodeCount() <<
"]");
928 format(
"Illegal node registration by %s.", class_name.c_str()));
934 template <
class GRAPH_T>
943 map = mrpt::make_aligned_shared<mrpt::maps::COccupancyGridMap2D>();
947 if (!m_map_is_cached)
951 map->copyMapContentFrom(*m_gridmap_cached);
954 if (acquisition_time)
956 *acquisition_time = m_map_acq_time;
961 template <
class GRAPH_T>
969 if (!m_map_is_cached)
978 if (acquisition_time)
980 *acquisition_time = m_map_acq_time;
986 template <
class GRAPH_T>
991 using namespace mrpt;
996 std::lock_guard<std::mutex> m_graph_lock(m_graph_section);
998 if (!constraint_t::is_3D())
1008 it = m_nodes_to_laser_scans2D.begin();
1009 it != m_nodes_to_laser_scans2D.end(); ++it)
1011 const TNodeID& curr_node = it->first;
1018 "LaserScan of nodeID: %lu is not present.",
1019 static_cast<unsigned long>(curr_node)));
1022 CPose3D scan_pose = getLSPoseForGridMapVisualization(curr_node);
1025 gridmap->insertObservation(curr_laser_scan.get(), &scan_pose);
1028 m_map_is_cached =
true;
1034 THROW_EXCEPTION(
"Not Implemented Yet. Method is to compute a COctoMap");
1041 template <
class GRAPH_T>
1049 mrpt::format(
"\nConfiguration file not found: \n%s\n", fname.c_str()));
1057 m_user_decides_about_output_dir = cfg_file.
read_bool(
1058 "GeneralConfiguration",
"user_decides_about_output_dir",
false,
false);
1060 "GeneralConfiguration",
"ground_truth_file_format",
"NavSimul",
false);
1063 int min_verbosity_level =
1064 cfg_file.
read_int(
"GeneralConfiguration",
"class_verbosity", 1,
false);
1065 this->setMinLoggingLevel(VerbosityLevel(min_verbosity_level));
1072 "VisualizationParameters",
"visualize_map",
true,
false);
1075 m_visualize_odometry_poses = cfg_file.
read_bool(
1076 "VisualizationParameters",
"visualize_odometry_poses",
true,
false);
1077 m_visualize_estimated_trajectory = cfg_file.
read_bool(
1078 "VisualizationParameters",
"visualize_estimated_trajectory",
true,
1083 "VisualizationParameters",
"visualize_ground_truth",
true,
false);
1085 m_visualize_SLAM_metric = cfg_file.
read_bool(
1086 "VisualizationParameters",
"visualize_SLAM_metric",
true,
false);
1089 m_enable_curr_pos_viewport = cfg_file.
read_bool(
1090 "VisualizationParameters",
"enable_curr_pos_viewport",
true,
false);
1091 m_enable_range_viewport = cfg_file.
read_bool(
1092 "VisualizationParameters",
"enable_range_viewport",
false,
false);
1093 m_enable_intensity_viewport = cfg_file.
read_bool(
1094 "VisualizationParameters",
"enable_intensity_viewport",
false,
false);
1096 m_node_reg->loadParams(fname);
1097 m_edge_reg->loadParams(fname);
1098 m_optimizer->loadParams(fname);
1100 m_has_read_config =
true;
1103 template <
class GRAPH_T>
1109 this->getParamsAsString(&str);
1114 template <
class GRAPH_T>
1119 using namespace std;
1121 stringstream ss_out;
1124 <<
"\n------------[ Graphslam_engine Problem Parameters ]------------" 1126 ss_out <<
"Config filename = " << m_config_fname
1129 ss_out <<
"Ground Truth File format = " << m_GT_file_format
1131 ss_out <<
"Ground Truth filename = " << m_fname_GT << std::endl;
1133 ss_out <<
"Visualize odometry = " 1134 << (m_visualize_odometry_poses ?
"TRUE" :
"FALSE") << std::endl;
1135 ss_out <<
"Visualize estimated trajectory = " 1136 << (m_visualize_estimated_trajectory ?
"TRUE" :
"FALSE")
1138 ss_out <<
"Visualize map = " 1139 << (m_visualize_map ?
"TRUE" :
"FALSE") << std::endl;
1140 ss_out <<
"Visualize Ground Truth = " 1141 << (m_visualize_GT ?
"TRUE" :
"FALSE") << std::endl;
1143 ss_out <<
"Visualize SLAM metric plot = " 1144 << (m_visualize_SLAM_metric ?
"TRUE" :
"FALSE") << std::endl;
1146 ss_out <<
"Enable curr. position viewport = " 1147 << (m_enable_curr_pos_viewport ?
"TRUE" :
"FALSE") << endl;
1148 ss_out <<
"Enable range img viewport = " 1149 << (m_enable_range_viewport ?
"TRUE" :
"FALSE") << endl;
1150 ss_out <<
"Enable intensity img viewport = " 1151 << (m_enable_intensity_viewport ?
"TRUE" :
"FALSE") << endl;
1153 ss_out <<
"-----------------------------------------------------------" 1155 ss_out << std::endl;
1158 *params_out = ss_out.str();
1163 template <
class GRAPH_T>
1167 std::cout << getParamsAsString();
1169 m_node_reg->printParams();
1170 m_edge_reg->printParams();
1171 m_optimizer->printParams();
1176 template <
class GRAPH_T>
1181 using namespace std;
1187 #if defined(MRPT_OS_APPLE) 1199 m_out_streams[fname]->fileOpenCorrectly(),
1200 mrpt::format(
"\nError while trying to open %s\n", fname.c_str()));
1204 m_out_streams[fname]->printf(
"# Mobile Robot Programming Toolkit (MRPT)\n");
1205 m_out_streams[fname]->printf(
"# http::/www.mrpt.org\n");
1206 m_out_streams[fname]->printf(
"# GraphSlamEngine Application\n");
1207 m_out_streams[fname]->printf(
1208 "# Automatically generated file - %s: %s\n", time_spec.c_str(),
1209 cur_date_str.c_str());
1210 m_out_streams[fname]->printf(
"%s\n\n", sep.c_str());
1215 template <
class GRAPH_T>
1225 viewp_range = scene->createViewport(
"viewp_range");
1227 m_win_manager->assignViewportParameters(&
x, &
y, &
w, &h);
1228 viewp_range->setViewportPosition(
x,
y, h,
w);
1230 m_win->unlockAccess3DScene();
1231 m_win->forceRepaint();
1236 template <
class GRAPH_T>
1240 std::lock_guard<std::mutex> m_graph_lock(m_graph_section);
1241 m_time_logger.enter(
"Visuals");
1243 m_node_reg->updateVisuals();
1244 m_edge_reg->updateVisuals();
1245 m_optimizer->updateVisuals();
1247 m_time_logger.leave(
"Visuals");
1251 template <
class GRAPH_T>
1259 if (m_last_laser_scan3D->hasRangeImage)
1267 m_last_laser_scan3D->load();
1268 range2D = m_last_laser_scan3D->rangeImage *
1270 img.setFromMatrix(range2D);
1274 viewp_range->setImageView(
img);
1275 m_win->unlockAccess3DScene();
1276 m_win->forceRepaint();
1282 template <
class GRAPH_T>
1292 viewp_intensity = scene->createViewport(
"viewp_intensity");
1294 m_win_manager->assignViewportParameters(&
x, &
y, &
w, &h);
1295 viewp_intensity->setViewportPosition(
x,
y,
w, h);
1297 m_win->unlockAccess3DScene();
1298 m_win->forceRepaint();
1302 template <
class GRAPH_T>
1309 if (m_last_laser_scan3D->hasIntensityImage)
1314 m_last_laser_scan3D->load();
1315 img = m_last_laser_scan3D->intensityImage;
1319 scene->getViewport(
"viewp_intensity");
1320 viewp_intensity->setImageView(
img);
1321 m_win->unlockAccess3DScene();
1322 m_win->forceRepaint();
1328 template <
class GRAPH_T>
1333 return this->initRobotModelVisualizationInternal(
p);
1336 template <
class GRAPH_T>
1345 template <
class GRAPH_T>
1353 template <
class GRAPH_T>
1363 scene->createViewport(
"curr_robot_pose_viewport");
1365 viewp->setCloneView(
"main");
1367 m_win_manager->assignViewportParameters(&
x, &
y, &
w, &h);
1368 viewp->setViewportPosition(
x,
y, h,
w);
1369 viewp->setTransparent(
false);
1370 viewp->getCamera().setAzimuthDegrees(90);
1371 viewp->getCamera().setElevationDegrees(90);
1372 viewp->setCustomBackgroundColor(
TColorf(205, 193, 197, 255));
1373 viewp->getCamera().setZoomDistance(30);
1374 viewp->getCamera().setOrthogonal();
1376 m_win->unlockAccess3DScene();
1377 m_win->forceRepaint();
1382 template <
class GRAPH_T>
1393 global_pose_t curr_robot_pose = this->getCurrentRobotPosEstimation();
1397 viewp->getCamera().setPointingAt(
CPose3D(curr_robot_pose));
1399 m_win->unlockAccess3DScene();
1400 m_win->forceRepaint();
1406 template <
class GRAPH_T>
1408 const std::string& fname_GT, std::vector<mrpt::poses::CPose2D>* gt_poses,
1409 std::vector<mrpt::system::TTimeStamp>* gt_timestamps )
1412 using namespace std;
1420 "\nGround-truth file %s was not found.\n" 1421 "Either specify a valid ground-truth filename or set set the " 1422 "m_visualize_GT flag to false\n",
1427 ASSERTMSG_(gt_poses,
"\nNo valid std::vector<pose_t>* was given\n");
1432 for (
size_t line_num = 0; file_GT.
readLine(curr_line); line_num++)
1434 vector<string> curr_tokens;
1439 curr_tokens.size() == constraint_t::state_length + 1,
1440 "\nGround Truth File doesn't seem to contain data as generated by " 1442 "GridMapNavSimul application.\n Either specify the GT file format " 1444 "visualize_ground_truth to false in the .ini file\n");
1450 gt_timestamps->push_back(timestamp);
1455 atof(curr_tokens[1].c_str()), atof(curr_tokens[2].c_str()),
1456 atof(curr_tokens[3].c_str()));
1457 gt_poses->push_back(curr_pose);
1464 template <
class GRAPH_T>
1466 const std::string& fname_GT, std::vector<mrpt::poses::CPose3D>* gt_poses,
1467 std::vector<mrpt::system::TTimeStamp>* gt_timestamps )
1472 template <
class GRAPH_T>
1474 const std::string& fname_GT, std::vector<mrpt::poses::CPose2D>* gt_poses,
1475 std::vector<mrpt::system::TTimeStamp>* gt_timestamps )
1478 using namespace std;
1487 "\nGround-truth file %s was not found.\n" 1488 "Either specify a valid ground-truth filename or set set the " 1489 "m_visualize_GT flag to false\n",
1495 "\nreadGTFileRGBD_TUM: Couldn't openGT file\n");
1496 ASSERTMSG_(gt_poses,
"No valid std::vector<pose_t>* was given");
1501 for (
size_t i = 0; file_GT.
readLine(curr_line); i++)
1503 if (curr_line.at(0) !=
'#')
1512 vector<string> curr_tokens;
1517 curr_tokens.size() == 8,
1518 "\nGround Truth File doesn't seem to contain data as specified in " 1520 "datasets.\n Either specify correct the GT file format or set " 1521 "visualize_ground_truth to false in the .ini file\n");
1525 quat.
r(atof(curr_tokens[7].c_str()));
1526 quat.x(atof(curr_tokens[4].c_str()));
1527 quat.y(atof(curr_tokens[5].c_str()));
1528 quat.z(atof(curr_tokens[6].c_str()));
1533 curr_coords[0] = atof(curr_tokens[1].c_str());
1534 curr_coords[1] = atof(curr_tokens[2].c_str());
1535 curr_coords[2] = atof(curr_tokens[3].c_str());
1538 pose_t curr_pose(curr_coords[0], curr_coords[1],
y);
1541 pose_diff = curr_pose;
1544 for (; file_GT.
readLine(curr_line);)
1546 vector<string> curr_tokens;
1549 curr_tokens.size() == 8,
1550 "\nGround Truth File doesn't seem to contain data as specified in " 1552 "datasets.\n Either specify correct the GT file format or set " 1553 "visualize_ground_truth to false in the .ini file\n");
1559 gt_timestamps->push_back(timestamp);
1564 quat.
r(atof(curr_tokens[7].c_str()));
1565 quat.
x(atof(curr_tokens[4].c_str()));
1566 quat.
y(atof(curr_tokens[5].c_str()));
1567 quat.
z(atof(curr_tokens[6].c_str()));
1572 curr_coords[0] = atof(curr_tokens[1].c_str());
1573 curr_coords[1] = atof(curr_tokens[2].c_str());
1574 curr_coords[2] = atof(curr_tokens[3].c_str());
1577 pose_t curr_pose(curr_coords[0], curr_coords[1],
y);
1579 curr_pose.x() -= pose_diff.x();
1580 curr_pose.y() -= pose_diff.y();
1581 curr_pose.phi() -= pose_diff.phi();
1583 gt_poses->push_back(curr_pose);
1591 template <
class GRAPH_T>
1595 using namespace std;
1606 const double tmpz[] = {
1607 cos(anglez), -sin(anglez), 0, sin(anglez), cos(anglez), 0, 0, 0, 1};
1613 const double tmpy[] = {cos(angley), 0, sin(angley), 0, 1, 0,
1614 -sin(angley), 0, cos(angley)};
1620 const double tmpx[] = {
1621 1, 0, 0, 0, cos(anglex), -sin(anglex), 0, sin(anglex), cos(anglex)};
1624 stringstream ss_out;
1625 ss_out <<
"\nConstructing the rotation matrix for the GroundTruth Data..." 1627 m_rot_TUM_to_MRPT = rotz * roty * rotx;
1629 ss_out <<
"Rotation matrices for optical=>MRPT transformation" << endl;
1630 ss_out <<
"rotz: " << endl << rotz << endl;
1631 ss_out <<
"roty: " << endl << roty << endl;
1632 ss_out <<
"rotx: " << endl << rotx << endl;
1633 ss_out <<
"Full rotation matrix: " << endl << m_rot_TUM_to_MRPT << endl;
1640 template <
class GRAPH_T>
1647 "\nqueryObserverForEvents method was called even though no Observer " 1648 "object was provided\n");
1651 std::map<std::string, bool> events_occurred;
1652 m_win_observer->returnEventsStruct(&events_occurred);
1653 m_request_to_exit = events_occurred.find(
"Ctrl+c")->second;
1656 if (events_occurred[m_keystroke_odometry])
1658 this->toggleOdometryVisualization();
1661 if (events_occurred[m_keystroke_GT])
1663 this->toggleGTVisualization();
1666 if (events_occurred[m_keystroke_map])
1668 this->toggleMapVisualization();
1671 if (events_occurred[m_keystroke_estimated_trajectory])
1673 this->toggleEstimatedTrajectoryVisualization();
1676 if (events_occurred[m_keystroke_pause_exec])
1678 this->togglePause();
1683 m_node_reg->notifyOfWindowEvents(events_occurred);
1684 m_edge_reg->notifyOfWindowEvents(events_occurred);
1685 m_optimizer->notifyOfWindowEvents(events_occurred);
1690 template <
class GRAPH_T>
1701 if (m_visualize_odometry_poses)
1704 obj->setVisibility(!
obj->isVisible());
1706 obj = scene->getByName(
"robot_odometry_poses");
1707 obj->setVisibility(!
obj->isVisible());
1711 dumpVisibilityErrorMsg(
"visualize_odometry_poses");
1714 m_win->unlockAccess3DScene();
1715 m_win->forceRepaint();
1719 template <
class GRAPH_T>
1733 obj->setVisibility(!
obj->isVisible());
1735 obj = scene->getByName(
"robot_GT");
1736 obj->setVisibility(!
obj->isVisible());
1740 dumpVisibilityErrorMsg(
"visualize_ground_truth");
1743 m_win->unlockAccess3DScene();
1744 m_win->forceRepaint();
1748 template <
class GRAPH_T>
1753 using namespace std;
1763 std::lock_guard<std::mutex> m_graph_lock(m_graph_section);
1764 num_of_nodes = m_graph.nodeCount();
1768 stringstream scan_name(
"");
1770 for (
int node_cnt = 0; node_cnt != num_of_nodes; ++node_cnt)
1774 scan_name <<
"laser_scan_";
1775 scan_name << node_cnt;
1782 obj->setVisibility(!
obj->isVisible());
1785 m_win->unlockAccess3DScene();
1786 m_win->forceRepaint();
1790 template <
class GRAPH_T>
1801 if (m_visualize_estimated_trajectory)
1804 obj->setVisibility(!
obj->isVisible());
1806 obj = scene->getByName(
"robot_estimated_traj");
1807 obj->setVisibility(!
obj->isVisible());
1811 dumpVisibilityErrorMsg(
"visualize_estimated_trajectory");
1814 m_win->unlockAccess3DScene();
1815 m_win->forceRepaint();
1819 template <
class GRAPH_T>
1827 "Cannot toggle visibility of specified object.\n" 1828 <<
"Make sure that the corresponding visualization flag (" << viz_flag
1829 <<
") is set to true in the .ini file.");
1830 std::this_thread::sleep_for(std::chrono::milliseconds(sleep_time));
1835 template <
class GRAPH_T>
1847 action || observation,
1848 "Neither action or observation contains valid data.");
1853 timestamp = observation->timestamp;
1858 timestamp = action->get(0)->timestamp;
1864 observations->begin();
1865 sens_it != observations->end(); ++sens_it)
1867 timestamp = (*sens_it)->timestamp;
1879 template <
class GRAPH_T>
1887 template <
class GRAPH_T>
1893 map_obj->setName(
"map");
1895 scene->insert(map_obj);
1896 this->m_win->unlockAccess3DScene();
1897 this->m_win->forceRepaint();
1900 template <
class GRAPH_T>
1904 nodes_to_laser_scans2D,
1912 using namespace std;
1923 map_update_timer.
Tic();
1926 std::set<mrpt::utils::TNodeID> nodes_set;
1933 m_graph.getAllNodes(nodes_set);
1940 nodes_set.insert(m_nodeID_max);
1947 node_it != nodes_set.end(); ++node_it)
1950 stringstream scan_name(
"");
1951 scan_name <<
"laser_scan_";
1952 scan_name << *node_it;
1958 search = nodes_to_laser_scans2D.find(*node_it);
1961 if (search != nodes_to_laser_scans2D.end() && search->second)
1963 scan_content = search->second;
1966 this->decimateLaserScan(
1967 *scan_content, &scan_decimated,
1978 scan_obj = mrpt::make_aligned_shared<CSetOfObjects>();
1983 m.getAs3DObject(scan_obj);
1985 scan_obj->setName(scan_name.str());
1986 this->setObjectPropsFromNodeID(*node_it, scan_obj);
1994 stringstream prev_scan_name(
"");
1995 prev_scan_name <<
"laser_scan_" << *node_it - 1;
1997 map_obj->getByName(prev_scan_name.str());
2000 scan_obj->setVisibility(prev_obj->isVisible());
2004 map_obj->insert(scan_obj);
2008 scan_obj = std::dynamic_pointer_cast<
CSetOfObjects>(scan_obj);
2013 scan_obj->setPose(scan_pose);
2018 "Laser scans of NodeID " << *node_it <<
"are empty/invalid");
2023 m_win->unlockAccess3DScene();
2024 m_win->forceRepaint();
2026 double elapsed_time = map_update_timer.
Tac();
2028 "updateMapVisualization took: " << elapsed_time <<
"s");
2032 template <
class GRAPH_T>
2038 viz_object->setColor_u8(m_optimized_map_color);
2042 template <
class GRAPH_T>
2046 const int keep_every_n_entries )
2051 size_t scan_size = laser_scan_in.
scan.
size();
2054 std::vector<float> new_scan(
2056 std::vector<char> new_validRange(scan_size);
2057 size_t new_scan_size = 0;
2058 for (
size_t i = 0; i != scan_size; i++)
2060 if (i % keep_every_n_entries == 0)
2062 new_scan[new_scan_size] = laser_scan_in.
scan[i];
2063 new_validRange[new_scan_size] = laser_scan_in.
validRange[i];
2068 new_scan_size, &new_scan[0], &new_validRange[0]);
2073 template <
class GRAPH_T>
2085 "Visualization of data was requested but no CDisplayWindow3D pointer " 2090 GT_cloud->setPointSize(1.0);
2091 GT_cloud->enablePointSmooth();
2092 GT_cloud->enableColorFromX(
false);
2093 GT_cloud->enableColorFromY(
false);
2094 GT_cloud->enableColorFromZ(
false);
2095 GT_cloud->setColor_u8(m_GT_color);
2096 GT_cloud->setName(
"GT_cloud");
2102 m_robot_model_size);
2106 scene->insert(GT_cloud);
2107 scene->insert(robot_model);
2108 m_win->unlockAccess3DScene();
2110 m_win_manager->assignTextMessageParameters(
2113 m_win_manager->addTextMessage(
2114 m_offset_x_left, -m_offset_y_GT,
mrpt::format(
"Ground truth path"),
2118 m_win->forceRepaint();
2123 template <
class GRAPH_T>
2132 if (m_visualize_GT && m_GT_poses_index < m_GT_poses.size())
2136 "Visualization of data was requested but no CDisplayWindow3D " 2137 "pointer was given");
2146 GT_cloud->insertPoint(
p.x(),
p.y(),
p.z());
2149 obj = scene->getByName(
"robot_GT");
2153 m_win->unlockAccess3DScene();
2154 m_win->forceRepaint();
2160 template <
class GRAPH_T>
2171 mrpt::make_aligned_shared<CPointCloud>();
2172 odometry_poses_cloud->setPointSize(1.0);
2173 odometry_poses_cloud->enablePointSmooth();
2174 odometry_poses_cloud->enableColorFromX(
false);
2175 odometry_poses_cloud->enableColorFromY(
false);
2176 odometry_poses_cloud->enableColorFromZ(
false);
2177 odometry_poses_cloud->setColor_u8(m_odometry_color);
2178 odometry_poses_cloud->setName(
"odometry_poses_cloud");
2182 "robot_odometry_poses", m_odometry_color, m_robot_model_size);
2186 scene->insert(odometry_poses_cloud);
2187 scene->insert(robot_model);
2188 m_win->unlockAccess3DScene();
2190 m_win_manager->assignTextMessageParameters(
2191 &m_offset_y_odometry,
2192 &m_text_index_odometry);
2193 m_win_manager->addTextMessage(
2194 m_offset_x_left, -m_offset_y_odometry,
mrpt::format(
"Odometry path"),
2196 m_text_index_odometry);
2198 m_win->forceRepaint();
2203 template <
class GRAPH_T>
2210 "Visualization of data was requested but no CDisplayWindow3D pointer " 2222 odometry_poses_cloud->insertPoint(
p.x(),
p.y(),
p.z());
2225 obj = scene->getByName(
"robot_odometry_poses");
2230 m_win->unlockAccess3DScene();
2231 m_win->forceRepaint();
2236 template <
class GRAPH_T>
2246 mrpt::make_aligned_shared<CSetOfLines>();
2247 estimated_traj_setoflines->setColor_u8(m_estimated_traj_color);
2248 estimated_traj_setoflines->setLineWidth(1.5);
2249 estimated_traj_setoflines->setName(
"estimated_traj_setoflines");
2252 estimated_traj_setoflines->appendLine(
2259 "robot_estimated_traj", m_estimated_traj_color, m_robot_model_size);
2263 if (m_visualize_estimated_trajectory)
2265 scene->insert(estimated_traj_setoflines);
2267 scene->insert(robot_model);
2268 m_win->unlockAccess3DScene();
2270 if (m_visualize_estimated_trajectory)
2272 m_win_manager->assignTextMessageParameters(
2273 &m_offset_y_estimated_traj,
2274 &m_text_index_estimated_traj);
2275 m_win_manager->addTextMessage(
2276 m_offset_x_left, -m_offset_y_estimated_traj,
2278 TColorf(m_estimated_traj_color),
2279 m_text_index_estimated_traj);
2282 m_win->forceRepaint();
2287 template <
class GRAPH_T>
2295 std::lock_guard<std::mutex> m_graph_lock(m_graph_section);
2296 ASSERT_(m_graph.nodeCount() != 0);
2301 if (m_visualize_estimated_trajectory)
2304 obj = scene->getByName(
"estimated_traj_setoflines");
2310 std::set<mrpt::utils::TNodeID> nodes_set;
2314 this->getNodeIDsOfEstimatedTrajectory(&nodes_set);
2315 estimated_traj_setoflines->clear();
2317 estimated_traj_setoflines->appendLine(
2323 nodes_set.insert(m_graph.nodeCount() - 1);
2329 it != nodes_set.end(); ++it)
2333 estimated_traj_setoflines->appendLineStrip(
p.x(),
p.y(),
p.z());
2339 obj = scene->getByName(
"robot_estimated_traj");
2342 pose_t curr_estimated_pos = m_graph.nodes[m_graph.nodeCount() - 1];
2343 robot_obj->
setPose(curr_estimated_pos);
2345 m_win->unlockAccess3DScene();
2346 m_win->forceRepaint();
2352 template <
class GRAPH_T>
2356 this->setRawlogFile(rawlog_fname);
2357 this->initTRGBDInfoFileParams();
2359 template <
class GRAPH_T>
2362 this->initTRGBDInfoFileParams();
2364 template <
class GRAPH_T>
2369 template <
class GRAPH_T>
2378 info_fname = dir + name_prefix + rawlog_filename + name_suffix;
2381 template <
class GRAPH_T>
2385 fields[
"Overall number of objects"] =
"";
2386 fields[
"Observations format"] =
"";
2389 template <
class GRAPH_T>
2393 using namespace std;
2400 "\nTRGBDInfoFileParams::parseFile: Couldn't open info file\n");
2403 size_t line_cnt = 0;
2410 if (curr_line.size() == 0)
break;
2414 while (info_file.
readLine(curr_line))
2417 vector<string> curr_tokens;
2428 it != fields.end(); ++it)
2432 it->second = value_part;
2441 template <
class GRAPH_T>
2456 fname =
"output_graph.graph";
2460 "Saving generated graph in VERTEX/EDGE format: " << fname);
2461 m_graph.saveToTextFile(fname);
2466 template <
class GRAPH_T>
2473 "\nsave3DScene was called even though enable_visuals flag is " 2474 "off.\nExiting...\n");
2483 "Could not fetch 3D Scene. Display window must already be closed.");
2494 "Removing CPlanarLaserScan from generated 3DScene...");
2495 scene->removeObject(laser_scan);
2507 fname =
"output_scene.3DScene";
2511 scene->saveToFile(fname);
2513 m_win->unlockAccess3DScene();
2514 m_win->forceRepaint();
2519 template <
class GRAPH_T>
2529 if (m_graph.nodeCount() < 4)
2535 m_nodeID_to_gt_indices[nodeID] = gt_index;
2542 double trans_diff = 0;
2543 double rot_diff = 0;
2545 size_t indices_size = m_nodeID_to_gt_indices.size();
2548 m_curr_deformation_energy = 0;
2554 m_nodeID_to_gt_indices.begin();
2562 pose_t prev_node_pos = m_graph.nodes[prev_it->first];
2563 pose_t prev_gt_pos = m_GT_poses[prev_it->second];
2570 index_it != m_nodeID_to_gt_indices.end(); index_it++)
2572 curr_node_pos = m_graph.nodes[index_it->first];
2573 curr_gt_pos = m_GT_poses[index_it->second];
2575 node_delta_pos = curr_node_pos - prev_node_pos;
2576 gt_delta = curr_gt_pos - prev_gt_pos;
2578 trans_diff = gt_delta.distanceTo(node_delta_pos);
2579 rot_diff = this->accumulateAngleDiffs(gt_delta, node_delta_pos);
2581 m_curr_deformation_energy += (pow(trans_diff, 2) + pow(rot_diff, 2));
2582 m_curr_deformation_energy /= indices_size;
2585 m_deformation_energy_vec.push_back(m_curr_deformation_energy);
2587 prev_node_pos = curr_node_pos;
2588 prev_gt_pos = curr_gt_pos;
2592 "Total deformation energy: " << m_curr_deformation_energy);
2597 template <
class GRAPH_T>
2603 template <
class GRAPH_T>
2617 template <
class GRAPH_T>
2621 using namespace std;
2627 ASSERT_(m_visualize_SLAM_metric);
2631 "Evolution of SLAM metric - Deformation Energy (1:1000)", 400, 300);
2633 m_win_plot->setPos(20, 50);
2636 m_win_plot->hold_off();
2637 m_win_plot->enableMousePanZoom(
true);
2642 template <
class GRAPH_T>
2647 ASSERT_(m_win_plot && m_visualize_SLAM_metric);
2650 std::vector<double>
x(m_deformation_energy_vec.size(), 0);
2651 std::vector<double>
y(m_deformation_energy_vec.size(), 0);
2652 for (
size_t i = 0; i !=
x.size(); i++)
2655 y[i] = m_deformation_energy_vec[i] * 1000;
2660 "Deformation Energy (x1000)");
2665 xmax = std::max_element(
x.begin(),
x.end());
2666 ymax = std::max_element(
y.begin(),
y.end());
2669 xmax !=
x.end() ? -(*xmax / 12) : -1,
2670 (xmax !=
x.end() ? *xmax : 1),
2672 (ymax !=
y.end() ? *ymax : 1));
2677 template <
class GRAPH_T>
2682 using namespace std;
2686 stringstream results_ss;
2687 results_ss <<
"Summary: " << std::endl;
2688 results_ss << this->header_sep << std::endl;
2689 results_ss <<
"\tProcessing time: " 2690 << m_time_logger.getMeanTime(
"proc_time") << std::endl;
2692 results_ss <<
"\tDataset Grab time: " << m_dataset_grab_time << std::endl;
2693 results_ss <<
"\tReal-time capable: " 2694 << (m_time_logger.getMeanTime(
"proc_time") < m_dataset_grab_time
2698 results_ss << m_edge_counter.getAsString();
2699 results_ss <<
"\tNum of Nodes: " << m_graph.nodeCount() << std::endl;
2703 std::string config_params = this->getParamsAsString();
2706 const std::string time_res = m_time_logger.getStatsAsText();
2707 const std::string output_res = this->getLogAsString();
2710 report_str->clear();
2712 *report_str += results_ss.str();
2713 *report_str += this->report_sep;
2715 *report_str += config_params;
2716 *report_str += this->report_sep;
2718 *report_str += time_res;
2719 *report_str += this->report_sep;
2721 *report_str += output_res;
2722 *report_str += this->report_sep;
2727 template <
class GRAPH_T>
2729 std::map<std::string, int>* node_stats,
2730 std::map<std::string, int>* edge_stats,
2734 using namespace std;
2737 ASSERTMSG_(node_stats,
"Invalid pointer to node_stats is given");
2738 ASSERTMSG_(edge_stats,
"Invalid pointer to edge_stats is given");
2740 if (m_nodeID_max == 0)
2746 (*node_stats)[
"nodes_total"] = m_nodeID_max + 1;
2750 it != m_edge_counter.end(); ++it)
2752 (*edge_stats)[it->first] = it->second;
2755 (*edge_stats)[
"loop_closures"] = m_edge_counter.getLoopClosureEdges();
2756 (*edge_stats)[
"edges_total"] = m_edge_counter.getTotalNumOfEdges();
2761 *timestamp = m_curr_timestamp;
2768 template <
class GRAPH_T>
2775 using namespace mrpt;
2780 "Output directory \"%s\" doesn't exist", output_dir_fname.c_str()));
2783 std::lock_guard<std::mutex> m_graph_lock(m_graph_section);
2791 fname = output_dir_fname +
"/" + m_class_name + ext;
2794 this->initResultsFile(fname);
2797 this->getDescriptiveReport(&report_str);
2798 m_out_streams[fname]->printf(
"%s", report_str.c_str());
2802 fname = output_dir_fname +
"/" +
"node_registrar" + ext;
2803 this->initResultsFile(fname);
2804 m_node_reg->getDescriptiveReport(&report_str);
2805 m_out_streams[fname]->printf(
"%s", report_str.c_str());
2809 fname = output_dir_fname +
"/" +
"edge_registrar" + ext;
2810 this->initResultsFile(fname);
2811 m_edge_reg->getDescriptiveReport(&report_str);
2812 m_out_streams[fname]->printf(
"%s", report_str.c_str());
2816 fname = output_dir_fname +
"/" +
"optimizer" + ext;
2817 this->initResultsFile(fname);
2818 m_optimizer->getDescriptiveReport(&report_str);
2819 m_out_streams[fname]->printf(
"%s", report_str.c_str());
2826 "# File includes the evolution of the SLAM metric. Implemented " 2827 "metric computes the \"deformation energy\" that is needed to " 2828 "transfer the estimated trajectory into the ground-truth " 2829 "trajectory (computed as sum of the difference between estimated " 2830 "trajectory and ground truth consecutive poses See \"A comparison " 2831 "of SLAM algorithms based on a graph of relations - W.Burgard et " 2832 "al.\", for more details on the metric.\n");
2834 fname = output_dir_fname +
"/" +
"SLAM_evaluation_metric" + ext;
2835 this->initResultsFile(fname);
2837 m_out_streams[fname]->printf(
"%s\n", desc.c_str());
2839 m_deformation_energy_vec.begin();
2840 vec_it != m_deformation_energy_vec.end(); ++vec_it)
2842 m_out_streams[fname]->printf(
"%f\n", *vec_it);
2848 template <
class GRAPH_T>
2852 const size_t model_size,
const pose_t& init_pose)
2856 ASSERTMSG_(!model_name.empty(),
"Model name provided is empty.");
2859 this->initRobotModelVisualization();
2860 model->setName(model_name);
2861 model->setColor_u8(model_color);
2862 model->setScale(model_size);
2863 model->setPose(init_pose);
2869 template <
class GRAPH_T>
2871 std::vector<double>* vec_out)
const 2876 *vec_out = m_deformation_energy_vec;
void updateOdometryVisualization()
Update odometry-only cloud with latest odometry estimation.
#define ASSERT_EQUAL_(__A, __B)
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
bool read_bool(const std::string §ion, const std::string &name, bool defaultValue, bool failIfNotFound=false) const
void queryObserverForEvents()
Query the observer instance for any user events.
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
void parseFile()
Parse the RGBD information file to gain information about the rawlog file contents.
void save3DScene(const std::string *fname_in=nullptr) const
Wrapper method around the COpenGLScene::saveToFile method.
std::shared_ptr< COpenGLViewport > Ptr
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
A set of object, which are referenced to the coordinates framework established in this object...
This namespace provides a OS-independent interface to many useful functions: filenames manipulation...
void updateGTVisualization()
Display the next ground truth position in the visualization window.
Create a GUI window and display plots with MATLAB-like interfaces and commands.
void computeMap() const
Compute the map of the environment based on the recorded measurements.
void toggleMapVisualization()
void computeSlamMetric(mrpt::utils::TNodeID nodeID, size_t gt_index)
Compare the SLAM result (estimated trajectory) with the GT path.
virtual void getNodeIDsOfEstimatedTrajectory(std::set< mrpt::utils::TNodeID > *nodes_set) const
Return the list of nodeIDs which make up robot trajectory.
A class for storing images as grayscale or RGB bitmaps.
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.
T y() const
Return y coordinate of the quaternion.
Interface for implementing node registration classes.
void initOdometryVisualization()
This class allows loading and storing values and vectors of different types from ".ini" files easily.
#define THROW_EXCEPTION(msg)
bool fileExists(const std::string &fileName)
Test if a given file (or directory) exists.
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::shared_ptr< CRenderizable > Ptr
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
std::string read_string(const std::string §ion, const std::string &name, const std::string &defaultValue, bool failIfNotFound=false) const
std::string timeToString(const mrpt::system::TTimeStamp t)
Convert a timestamp into this textual form (UTC): HH:MM:SS.MMMMMM.
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. ...
const Scalar * const_iterator
const_iterator find(const KEY &key) const
std::shared_ptr< CObservation2DRangeScan > Ptr
void initGTVisualization()
void Tic()
Starts the stopwatch.
GLsizei GLsizei GLuint * obj
std::shared_ptr< CObservationOdometry > Ptr
std::shared_ptr< COccupancyGridMap2D > Ptr
GLubyte GLubyte GLubyte GLubyte w
virtual void monitorNodeRegistration(bool registered=false, std::string class_name="Class")
Assert that the given nodes number matches the registered graph nodes, otherwise throw exception...
void loadParams(const std::string &fname)
Read the configuration variables from the .ini file specified by the user.
mrpt::system::TTimeStamp getCurrentLocalTime()
Returns the current (local) time.
virtual void getRobotEstimatedTrajectory(typename GRAPH_T::global_poses_t *graph_poses) const
int read_int(const std::string §ion, const std::string &name, int defaultValue, bool failIfNotFound=false) const
void updateAllVisuals()
Wrapper around the deciders/optimizer updateVisuals methods.
std::shared_ptr< COctoMap > Ptr
GRAPH_T::constraint_t constraint_t
Type of graph constraints.
static double accumulateAngleDiffs(const mrpt::poses::CPose2D &p1, const mrpt::poses::CPose2D &p2)
This base provides a set of functions for maths stuff.
static const std::string report_sep
T r() const
Return r coordinate of the quaternion.
GRAPH_T::constraint_t::type_value pose_t
Type of underlying poses (2D/3D).
uint64_t TNodeID
The type for node IDs in graphs of different types.
void alignOpticalWithMRPTFrame()
void initTRGBDInfoFileParams()
This CStream derived class allow using a file as a write-only, binary stream.
void execDijkstraNodesEstimation()
Wrapper around the GRAPH_T::dijkstra_nodes_estimate.
void updateIntensityImageViewport()
In RGB-D TUM Datasets update the Intensity image displayed in a seperate viewport.
This class implements a high-performance stopwatch.
std::shared_ptr< CPlanarLaserScan > Ptr
std::shared_ptr< CSetOfObjects > Ptr
This namespace contains representation of robot actions and observations.
mrpt::utils::ContainerReadOnlyProxyAccessor< std::vector< char > > validRange
It's false (=0) on no reflected rays, referenced to elements in scan.
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
virtual void setObjectPropsFromNodeID(const mrpt::utils::TNodeID nodeID, mrpt::opengl::CSetOfObjects::Ptr &viz_object)
Set the properties of the map visual object based on the nodeID that it was produced by...
This object renders a 2D laser scan by means of three elements: the points, the line along end-points...
virtual void updateCurrPosViewport()
Update the viewport responsible for displaying the graph-building procedure in the estimated position...
std::shared_ptr< CSensoryFrame > Ptr
std::shared_ptr< CAxis > Ptr
mrpt::opengl::CSetOfObjects::Ptr initRobotModelVisualizationInternal(const mrpt::poses::CPose2D &p_unused)
Method to help overcome the partial template specialization restriction of C++.
CGraphSlamEngine(const std::string &config_file, const std::string &rawlog_fname="", const std::string &fname_GT="", mrpt::graphslam::CWindowManager *win_manager=NULL, mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_T > *node_reg=NULL, mrpt::graphslam::deciders::CEdgeRegistrationDecider< GRAPH_T > *edge_reg=NULL, mrpt::graphslam::optimizers::CGraphSlamOptimizer< GRAPH_T > *optimizer=NULL)
Constructor of CGraphSlamEngine class template.
#define MRPT_LOG_WARN_STREAM(__CONTENTS)
uint64_t TNodeID
The type for node IDs in graphs of different types.
void updateEstimatedTrajectoryVisualization(bool full_update=false)
Update the Esstimated robot trajectory with the latest estimated robot position.
std::shared_ptr< CObservation > Ptr
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.
#define INVALID_TIMESTAMP
Represents an invalid timestamp, where applicable.
void toggleEstimatedTrajectoryVisualization()
std::map< std::string, mrpt::utils::CFileOutputStream * >::iterator fstreams_out_it
Map for iterating over output file streams.
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()
void tokenize(const std::string &inString, const std::string &inDelimiters, std::deque< std::string > &outTokens, bool skipBlankTokens=true) noexcept
Tokenizes a string according to a set of delimiting characters.
virtual bool _execGraphSlamStep(mrpt::obs::CActionCollection::Ptr &action, mrpt::obs::CSensoryFrame::Ptr &observations, mrpt::obs::CObservation::Ptr &observation, size_t &rawlog_entry)
Main class method responsible for parsing each measurement and for executing graphSLAM.
mrpt::opengl::CSetOfObjects::Ptr initRobotModelVisualization()
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.
GRAPH_T::global_pose_t global_pose_t
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
static void readGTFile(const std::string &fname_GT, std::vector< mrpt::poses::CPose2D > *gt_poses, std::vector< mrpt::system::TTimeStamp > *gt_timestamps=NULL)
Parse the ground truth .txt file and fill in the corresponding gt_poses vector.
T x() const
Return x coordinate of the quaternion.
std::shared_ptr< CActionCollection > Ptr
#define MRPT_LOG_INFO_STREAM(__CONTENTS)
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.
void updateMapVisualization(const std::map< mrpt::utils::TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > &nodes_to_laser_scans2D, bool full_update=false)
Update the map visualization based on the current graphSLAM state.
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
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)
CSetOfObjects::Ptr CornerXYZ(float scale=1.0)
Returns three arrows representing a X,Y,Z 3D corner.
std::map< std::string, int >::const_iterator const_iterator
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::utils::CSerializable) is of t...
std::shared_ptr< COpenGLScene > Ptr
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.
double Tac()
Stops the stopwatch.
std::deque< CObservation::Ptr >::const_iterator const_iterator
You can use CSensoryFrame::begin to get a iterator to the first element.
A RGB color - floats in the range [0,1].
A matrix of dynamic size.
std::shared_ptr< CSetOfLines > Ptr
#define ASSERT_FILE_EXISTS_(FIL)
CRenderizable & setPose(const mrpt::poses::CPose3D &o)
Set the 3D pose from a mrpt::poses::CPose3D object (return a ref to this)
void loadFromVectors(size_t nRays, const float *scanRanges, const char *scanValidity)
void getMap(mrpt::maps::COccupancyGridMap2D::Ptr map, mrpt::system::TTimeStamp *acquisition_time=NULL) const
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.
virtual mrpt::poses::CPose3D getLSPoseForGridMapVisualization(const mrpt::utils::TNodeID nodeID) const
return the 3D Pose of a LaserScan that is to be visualized.
Classes for creating GUI windows for 2D and 3D visualization.
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 ...
mrpt::utils::ContainerReadOnlyProxyAccessor< std::vector< float > > scan
The range values of the scan, in meters.
std::shared_ptr< CPointCloud > Ptr
std::string extractFileName(const std::string &filePath)
Extract just the name (without extension) of a filename from a complete path plus name plus extension...
A set of independent lines (or segments), one line with its own start and end positions (X...
T z() const
Return z coordinate of the quaternion.
bool strCmpI(const std::string &s1, const std::string &s2)
Return true if the two strings are equal (case insensitive)
#define MRPT_LOG_DEBUG_STREAM(__CONTENTS)
void initCurrPosViewport()
#define ASSERTMSG_(f, __ERROR_MSG)
#define MRPT_LOG_ERROR_STREAM(__CONTENTS)
bool insertObservation(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose=NULL)
Insert the observation information into this map.
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 rpy(T &roll, T &pitch, T &yaw) const
Return the yaw, pitch & roll angles associated to quaternion.
mrpt::opengl::CSetOfObjects::Ptr setCurrentPositionModel(const std::string &model_name, const mrpt::utils::TColor &model_color=mrpt::utils::TColor(0, 0, 0), const size_t model_size=1, const pose_t &init_pose=pose_t())
Set the opengl model that indicates the latest position of the trajectory at hand.
void initSlamMetricVisualization()
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 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.