21 template <
class GRAPH_T>
24 this->initializeLoggers(
"CLoopCloserERD");
25 m_edge_types_to_nums[
"ICP2D"] = 0;
26 m_edge_types_to_nums[
"LC"] = 0;
30 template <
class GRAPH_T>
33 for (
auto it = m_node_optimal_paths.begin();
34 it != m_node_optimal_paths.end(); ++it)
40 template <
class GRAPH_T>
48 this->m_time_logger.enter(
"updateState");
60 getObservation<CObservation2DRangeScan>(observations, observation);
63 m_last_laser_scan2D = scan;
67 if (!m_first_laser_scan)
69 m_first_laser_scan = m_last_laser_scan2D;
73 size_t num_registered =
74 absDiff(this->m_last_total_num_nodes, this->m_graph->nodeCount());
75 bool registered_new_node = num_registered > 0;
77 if (registered_new_node)
80 registered_new_node =
true;
84 if (!this->m_override_registered_nodes_check)
86 if (!((num_registered == 1) ^
87 (num_registered == 2 && m_is_first_time_node_reg)))
90 "Invalid number of registered nodes since last call to " 93 << num_registered <<
"\" new nodes.");
104 if (m_is_first_time_node_reg)
107 "Assigning first laserScan to the graph root node.");
108 this->m_nodes_to_laser_scans2D[this->m_graph->root] =
110 m_is_first_time_node_reg =
false;
114 this->m_nodes_to_laser_scans2D[this->m_graph->nodeCount() - 1] =
117 if (m_laser_params.use_scan_matching)
120 this->addScanMatchingEdges(this->m_graph->nodeCount() - 1);
124 m_partitions_full_update =
125 ((this->m_graph->nodeCount() %
126 m_lc_params.full_partition_per_nodes) == 0 ||
127 this->m_just_inserted_lc)
130 this->updateMapPartitions(
131 m_partitions_full_update, num_registered == 2);
135 this->checkPartitionsForLC(&partitions_for_LC);
136 this->evaluatePartitionsForLC(partitions_for_LC);
138 if (m_visualize_curr_node_covariance)
140 this->execDijkstraProjection();
143 this->m_last_total_num_nodes = this->m_graph->nodeCount();
146 this->m_time_logger.leave(
"updateState");
151 template <
class GRAPH_T>
154 std::set<mrpt::graphs::TNodeID>* nodes_set)
160 int fetched_nodeIDs = 0;
161 for (
int nodeID_i = static_cast<int>(curr_nodeID) - 1;
162 ((fetched_nodeIDs <= this->m_laser_params.prev_nodes_for_ICP) &&
167 nodes_set->insert(nodeID_i);
172 template <
class GRAPH_T>
178 using namespace mrpt;
186 std::set<TNodeID> nodes_set;
187 this->fetchNodeIDsForScanMatching(curr_nodeID, &nodes_set);
190 for (
unsigned long node_it : nodes_set)
196 "Fetching laser scan for nodes: " << node_it <<
"==> " 200 this->getICPEdge(node_it, curr_nodeID, &rel_edge, &icp_info);
201 if (!found_edge)
continue;
208 m_laser_params.goodness_threshold_win.addNewMeasurement(
211 double goodness_thresh =
212 m_laser_params.goodness_threshold_win.getMedian() *
213 m_consec_icp_constraint_factor;
214 bool accept_goodness = icp_info.
goodness > goodness_thresh;
216 "Curr. Goodness: " << icp_info.
goodness 217 <<
"|\t Threshold: " << goodness_thresh <<
" => " 218 << (accept_goodness ?
"ACCEPT" :
"REJECT"));
222 bool accept_mahal_distance = this->mahalanobisDistanceOdometryToICPEdge(
223 node_it, curr_nodeID, rel_edge);
226 if (accept_goodness && accept_mahal_distance)
228 this->registerNewEdge(node_it, curr_nodeID, rel_edge);
234 template <
class GRAPH_T>
242 this->m_time_logger.enter(
"getICPEdge");
259 "TGetICPEdgeAdParams:\n" 266 bool from_success = this->getPropsOfNodeID(
267 from, &from_pose, from_scan, from_params);
270 bool to_success = this->getPropsOfNodeID(to, &to_pose, to_scan, to_params);
272 if (!from_success || !to_success)
276 << from <<
" or node #" << to
277 <<
" doesn't contain a valid LaserScan. Ignoring this...");
290 initial_estim = to_pose - from_pose;
294 "from_pose: " << from_pose <<
"| to_pose: " << to_pose
295 <<
"| init_estim: " << initial_estim);
297 range_ops_t::getICPEdge(
298 *from_scan, *to_scan, rel_edge, &initial_estim, icp_info);
301 this->m_time_logger.leave(
"getICPEdge");
306 template <
class GRAPH_T>
309 const std::map<mrpt::graphs::TNodeID, node_props_t>& group_params,
320 auto search = group_params.find(nodeID);
322 if (search == group_params.end())
328 *node_props = search->second;
338 template <
class GRAPH_T>
347 bool filled_pose =
false;
348 bool filled_scan =
false;
355 *pose = node_props->
pose;
359 if (node_props->
scan)
361 scan = node_props->
scan;
368 !(filled_pose ^ filled_scan),
370 "Either BOTH or NONE of the filled_pose, filled_scan should be set." 372 static_cast<unsigned long>(nodeID)));
380 auto search = this->m_graph->nodes.find(nodeID);
381 if (search != this->m_graph->nodes.end())
383 *pose = search->second;
393 auto search = this->m_nodes_to_laser_scans2D.find(nodeID);
394 if (search != this->m_nodes_to_laser_scans2D.end())
396 scan = search->second;
401 return filled_pose && filled_scan;
404 template <
class GRAPH_T>
409 this->m_time_logger.enter(
"LoopClosureEvaluation");
412 using namespace mrpt;
415 partitions_for_LC->clear();
419 map<int, std::vector<uint32_t>>::iterator finder;
421 if (m_partitions_full_update)
423 m_partitionID_to_prev_nodes_list.clear();
428 for (
auto partitions_it = m_curr_partitions.begin();
429 partitions_it != m_curr_partitions.end();
430 ++partitions_it, ++partitionID)
434 if (m_lc_params.LC_check_curr_partition_only)
436 bool curr_node_in_curr_partition =
438 partitions_it->begin(), partitions_it->end(),
439 this->m_graph->nodeCount() - 1)) != partitions_it->end());
440 if (!curr_node_in_curr_partition)
447 finder = m_partitionID_to_prev_nodes_list.find(partitionID);
448 if (finder == m_partitionID_to_prev_nodes_list.end())
451 m_partitionID_to_prev_nodes_list.insert(
452 make_pair(partitionID, *partitions_it));
456 if (*partitions_it == finder->second)
466 finder->second = *partitions_it;
471 int curr_node_index = 1;
472 size_t prev_nodeID = *(partitions_it->begin());
473 for (
auto it = partitions_it->begin() + 1; it != partitions_it->end();
474 ++it, ++curr_node_index)
476 size_t curr_nodeID = *it;
480 if ((curr_nodeID - prev_nodeID) > m_lc_params.LC_min_nodeid_diff)
484 int num_after_nodes = partitions_it->size() - curr_node_index;
485 int num_before_nodes = partitions_it->size() - num_after_nodes;
486 if (num_after_nodes >= m_lc_params.LC_min_remote_nodes &&
487 num_before_nodes >= m_lc_params.LC_min_remote_nodes)
490 "Found potential loop closures:" 492 <<
"\tPartitionID: " << partitionID << endl
498 <<
"\t" << prev_nodeID <<
" ==> " << curr_nodeID << endl
499 <<
"\tNumber of LC nodes: " << num_after_nodes);
500 partitions_for_LC->push_back(*partitions_it);
507 prev_nodeID = curr_nodeID;
510 "Successfully checked partition: " << partitionID);
513 this->m_time_logger.leave(
"LoopClosureEvaluation");
517 template <
class GRAPH_T>
522 using namespace mrpt;
526 this->m_time_logger.enter(
"LoopClosureEvaluation");
528 if (partitions.size() == 0)
return;
531 "Evaluating partitions for loop closures...\n%s\n",
532 this->header_sep.c_str());
535 for (
auto partition : partitions)
538 std::vector<uint32_t> groupA, groupB;
539 this->splitPartitionToGroups(partition, &groupA, &groupB, 5);
543 this->generateHypotsPool(groupA, groupB, &hypots_pool);
546 CMatrixDouble consist_matrix(hypots_pool.size(), hypots_pool.size());
547 this->generatePWConsistenciesMatrix(
548 groupA, groupB, hypots_pool, &consist_matrix);
552 this->evalPWConsistenciesMatrix(
553 consist_matrix, hypots_pool, &valid_hypots);
556 if (valid_hypots.size())
559 for (
auto it = valid_hypots.begin(); it != valid_hypots.end(); ++it)
561 this->registerHypothesis(**it);
566 for (
auto it = hypots_pool.begin(); it != hypots_pool.end(); ++it)
573 this->m_time_logger.leave(
"LoopClosureEvaluation");
578 template <
class GRAPH_T>
588 valid_hypots->clear();
593 bool valid_lambda_ratio =
594 this->computeDominantEigenVector(consist_matrix, &u,
false);
595 if (!valid_lambda_ratio)
return;
603 double dot_product = 0;
604 for (
int i = 0; i != w.size(); ++i)
611 double potential_dot_product =
615 "current: %f | potential_dot_product: %f", dot_product,
616 potential_dot_product);
617 if (potential_dot_product > dot_product)
620 dot_product = potential_dot_product;
630 cout <<
"Outcome of discretization: " << w.transpose() << endl;
634 if (!w.asEigen().isZero())
636 for (
int wi = 0; wi != w.size(); ++wi)
643 valid_hypots->push_back(this->findHypotByID(hypots_pool, wi));
652 template <
class GRAPH_T>
654 std::vector<uint32_t>& partition, std::vector<uint32_t>* groupA,
655 std::vector<uint32_t>* groupB,
int max_nodes_in_group)
659 using namespace mrpt;
667 max_nodes_in_group == -1 || max_nodes_in_group > 0,
669 "Value %d not permitted for max_nodes_in_group" 670 "Either use a positive integer, " 671 "or -1 for non-restrictive partition size",
672 max_nodes_in_group));
677 size_t index_to_split = 1;
678 for (
auto it = partition.begin() + 1; it != partition.end();
679 ++it, ++index_to_split)
683 if ((curr_nodeID - prev_nodeID) > m_lc_params.LC_min_nodeid_diff)
688 prev_nodeID = curr_nodeID;
690 ASSERTDEB_(partition.size() > index_to_split);
693 *groupA = std::vector<uint32_t>(
694 partition.begin(), partition.begin() + index_to_split);
695 *groupB = std::vector<uint32_t>(
696 partition.begin() + index_to_split, partition.end());
698 if (max_nodes_in_group != -1)
701 if (groupA->size() >
static_cast<size_t>(max_nodes_in_group))
703 *groupA = std::vector<uint32_t>(
704 groupA->begin(), groupA->begin() + max_nodes_in_group);
707 if (groupB->size() >
static_cast<size_t>(max_nodes_in_group))
709 *groupB = std::vector<uint32_t>(
710 groupB->end() - max_nodes_in_group, groupB->end());
718 template <
class GRAPH_T>
720 const std::vector<uint32_t>& groupA,
const std::vector<uint32_t>& groupB,
724 using namespace mrpt;
729 "generateHypotsPool: Given hypotsp_t pointer is invalid.");
730 generated_hypots->clear();
735 <<
" - size: " << groupA.size() << endl);
738 <<
" - size: " << groupB.size() << endl);
752 size_t nodes_count = groupA.size();
756 nodes_count == p.size(),
758 "Size mismatch between nodeIDs in group [%lu]" 759 " and corresponding properties map [%lu]",
760 nodes_count, p.size()));
766 int hypot_counter = 0;
767 int invalid_hypots = 0;
770 for (
unsigned int b_it : groupB)
772 for (
unsigned int a_it : groupA)
781 hypot->id = hypot_counter++;
796 fillNodePropsFromGroupParams(
800 fillNodePropsFromGroupParams(
822 bool found_edge = this->getICPEdge(
823 b_it, a_it, &edge, &icp_info, icp_ad_params);
825 hypot->setEdge(edge);
832 double goodness_thresh =
833 m_laser_params.goodness_threshold_win.getMedian() *
834 m_lc_icp_constraint_factor;
835 bool accept_goodness = icp_info.
goodness > goodness_thresh;
837 "generateHypotsPool:\nCurr. Goodness: " 838 << icp_info.
goodness <<
"|\t Threshold: " << goodness_thresh
839 <<
" => " << (accept_goodness ?
"ACCEPT" :
"REJECT")
842 if (!found_edge || !accept_goodness)
844 hypot->is_valid =
false;
847 generated_hypots->push_back(hypot);
852 delete icp_ad_params;
856 "Generated pool of hypotheses...\tsize = " 857 << generated_hypots->size()
858 <<
"\tinvalid hypotheses: " << invalid_hypots);
864 template <
class GRAPH_T>
870 using namespace mrpt;
875 this->m_time_logger.enter(
"DominantEigenvectorComputation");
877 double lambda1, lambda2;
878 bool is_valid_lambda_ratio =
false;
880 if (use_power_method)
883 "\nPower method for computing the first two " 884 "eigenvectors/eigenvalues hasn't been implemented yet\n");
889 std::vector<double> eigvals;
890 consist_matrix.
eig(eigvecs, eigvals);
895 eigvecs.
size() == eigvals.size() &&
896 consist_matrix.
cols() == eigvals.size(),
898 "Size of eigvecs \"%lu\"," 900 "consist_matrix \"%lu\" don't match",
901 static_cast<unsigned long>(eigvecs.
size()),
902 static_cast<unsigned long>(eigvals.size()),
903 static_cast<unsigned long>(consist_matrix.
size())));
906 for (
int i = 0; i != eigvec->
size(); ++i)
907 (*eigvec)[i] = std::abs(eigvecs(i, eigvecs.
cols() - 1));
909 lambda1 = eigvals[eigvals.size() - 1];
910 lambda2 = eigvals[eigvals.size() - 2];
918 "Bad lambda2 value: " 919 << lambda2 <<
" => Skipping current evaluation." << endl);
922 double curr_lambda_ratio = lambda1 / lambda2;
924 "lambda1 = " << lambda1 <<
" | lambda2 = " << lambda2
925 <<
"| ratio = " << curr_lambda_ratio << endl);
927 is_valid_lambda_ratio =
928 (curr_lambda_ratio > m_lc_params.LC_eigenvalues_ratio_thresh);
930 this->m_time_logger.leave(
"DominantEigenvectorComputation");
931 return is_valid_lambda_ratio;
936 template <
class GRAPH_T>
938 const std::vector<uint32_t>& groupA,
const std::vector<uint32_t>& groupB,
944 using namespace mrpt;
951 consist_matrix,
"Invalid pointer to the Consistency matrix is given");
953 static_cast<unsigned long>(consist_matrix->
rows()) ==
954 hypots_pool.size() &&
955 static_cast<unsigned long>(consist_matrix->
rows()) ==
957 "Consistency matrix dimensions aren't equal to the hypotheses pool " 961 ">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>" 963 <<
"In generatePWConsistencyMatrix:\n" 966 <<
"\tHypots pool Size: " << hypots_pool.size());
969 for (
auto b1_it = groupB.begin(); b1_it != groupB.end(); ++b1_it)
974 for (
auto b2_it = b1_it + 1; b2_it != groupB.end(); ++b2_it)
979 for (
auto a1_it = groupA.begin(); a1_it != groupA.end(); ++a1_it)
983 this->findHypotByEnds(hypots_pool,
b2,
a1);
988 for (
auto a2_it = a1_it + 1; a2_it != groupA.end(); ++a2_it)
992 this->findHypotByEnds(hypots_pool,
b1,
a2);
999 if (hypot_b2_a1->is_valid && hypot_b1_a2->is_valid)
1005 extracted_hypots.push_back(hypot_b2_a1);
1006 extracted_hypots.push_back(hypot_b1_a2);
1008 paths_t* curr_opt_paths =
nullptr;
1009 if (groupA_opt_paths || groupB_opt_paths)
1011 curr_opt_paths =
new paths_t();
1018 if (groupA_opt_paths)
1020 const path_t* p = this->findPathByEnds(
1021 *groupA_opt_paths,
a1,
a2,
true);
1022 curr_opt_paths->push_back(*p);
1026 curr_opt_paths->push_back(
path_t());
1029 if (groupB_opt_paths)
1031 const path_t* p = this->findPathByEnds(
1032 *groupB_opt_paths,
b1,
b2,
true);
1033 curr_opt_paths->push_back(*p);
1037 curr_opt_paths->push_back(
path_t());
1041 consistency = this->generatePWConsistencyElement(
1042 a1,
a2,
b1,
b2, extracted_hypots, curr_opt_paths);
1044 delete curr_opt_paths;
1059 int id1 = hypot_b2_a1->id;
1060 int id2 = hypot_b1_a2->id;
1062 (*consist_matrix)(id1, id2) = consistency;
1063 (*consist_matrix)(id2, id1) = consistency;
1080 template <
class GRAPH_T>
1087 using namespace std;
1088 using namespace mrpt;
1116 const path_t* path_a1_a2;
1117 if (!opt_paths || opt_paths->begin()->isEmpty())
1120 "Running dijkstra [a1] " <<
a1 <<
" => [a2] " <<
a2);
1121 execDijkstraProjection(
a1,
a2);
1122 path_a1_a2 = this->queryOptimalPath(
a2);
1127 path_a1_a2 = &(*opt_paths->begin());
1133 const path_t* path_b1_b2;
1134 if (!opt_paths || opt_paths->rend()->isEmpty())
1137 "Running djkstra [b1] " <<
b1 <<
" => [b2] " <<
b2);
1138 execDijkstraProjection(
b1,
b2);
1139 path_b1_b2 = this->queryOptimalPath(
b2);
1143 path_b1_b2 = &(*opt_paths->rbegin());
1151 hypot_t* hypot_b1_a2 = this->findHypotByEnds(hypots,
b1,
a2);
1153 hypot_t* hypot_b2_a1 = this->findHypotByEnds(hypots,
b2,
a1);
1158 res_transform += hypot_b1_a2->getInverseEdge();
1160 res_transform += hypot_b2_a1->getEdge();
1163 "\n-----------Resulting Transformation----------- Hypots: #" 1164 << hypot_b1_a2->id <<
", #" << hypot_b2_a1->id << endl
1165 <<
"a1 --> a2 => b1 --> b2 => a1: " <<
a1 <<
" --> " <<
a2 <<
" => " 1166 <<
b1 <<
" --> " <<
b2 <<
" => " <<
a1 << endl
1167 << res_transform << endl
1169 <<
"DIJKSTRA: " <<
a1 <<
" --> " <<
a2 <<
": " 1171 <<
"DIJKSTRA: " <<
b1 <<
" --> " <<
b2 <<
": " 1173 <<
"hypot_b1_a2(inv):\n" 1174 << hypot_b1_a2->getInverseEdge() << endl
1176 << hypot_b2_a1->getEdge() << endl);
1179 typename pose_t::vector_t T;
1180 res_transform.getMeanVal().asVector(T);
1184 res_transform.getCovariance(cov_mat);
1191 double consistency_elem = exp(exponent);
1198 return consistency_elem;
1202 template <
class GRAPH_T>
1208 using namespace mrpt;
1211 const path_t* res =
nullptr;
1213 for (
auto cit = vec_paths.begin(); cit != vec_paths.end(); ++cit)
1215 if (cit->getSource() == src && cit->getDestination() == dst)
1221 if (throw_exc && !res)
1224 "Path for %lu => %lu is not found. Exiting...\n",
1225 static_cast<unsigned long>(src), static_cast<unsigned long>(dst)));
1231 template <
class GRAPH_T>
1238 using namespace std;
1240 for (
auto v_cit = vec_hypots.begin(); v_cit != vec_hypots.end(); v_cit++)
1242 if ((*v_cit)->hasEnds(from, to))
1261 template <
class GRAPH_T>
1264 const hypotsp_t& vec_hypots,
size_t id,
bool throw_exc)
1268 for (
auto v_cit = vec_hypots.begin(); v_cit != vec_hypots.end(); v_cit++)
1270 if ((*v_cit)->id ==
id)
1287 template <
class GRAPH_T>
1292 using namespace std;
1293 using namespace mrpt;
1301 this->m_time_logger.enter(
"Dijkstra Projection");
1302 const std::string dijkstra_end =
1303 "----------- Done with Dijkstra Projection... ----------";
1309 (ending_node >= 0 && ending_node < this->m_graph->nodeCount()));
1311 starting_node != ending_node,
"Starting and Ending nodes coincede");
1314 stringstream ss_debug(
"");
1315 ss_debug <<
"Executing Dijkstra Projection: " << starting_node <<
" => ";
1318 ss_debug <<
"..." << endl;
1322 ss_debug << ending_node << endl;
1325 if (this->m_graph->nodeCount() < m_dijkstra_node_count_thresh)
1331 std::vector<bool> visited_nodes(this->m_graph->nodeCount(),
false);
1332 m_node_optimal_paths.clear();
1335 std::map<TNodeID, std::set<TNodeID>> neighbors_of;
1336 this->m_graph->getAdjacencyMatrix(neighbors_of);
1341 std::set<path_t*> pool_of_paths;
1343 std::set<TNodeID> starting_node_neighbors(neighbors_of.at(starting_node));
1344 for (
unsigned long starting_node_neighbor : starting_node_neighbors)
1346 auto* path_between_neighbors =
new path_t();
1347 this->getMinUncertaintyPath(
1348 starting_node, starting_node_neighbor, path_between_neighbors);
1350 pool_of_paths.insert(path_between_neighbors);
1353 visited_nodes.at(starting_node) =
true;
1370 for (
auto it = visited_nodes.begin(); it != visited_nodes.end(); ++it)
1383 if (visited_nodes.at(ending_node))
1386 this->m_time_logger.leave(
"Dijkstra Projection");
1391 path_t* optimal_path = this->popMinUncertaintyPath(&pool_of_paths);
1416 if (!visited_nodes.at(dest))
1418 m_node_optimal_paths[dest] = optimal_path;
1419 visited_nodes.at(dest) =
true;
1425 &pool_of_paths, *optimal_path, neighbors_of.at(dest));
1430 this->m_time_logger.leave(
"Dijkstra Projection");
1434 template <
class GRAPH_T>
1436 std::set<path_t*>* pool_of_paths,
const path_t& current_path,
1437 const std::set<mrpt::graphs::TNodeID>& neighbors)
const 1440 using namespace std;
1451 for (
unsigned long neighbor : neighbors)
1453 if (neighbor == second_to_last_node)
continue;
1456 path_t path_between_nodes;
1457 this->getMinUncertaintyPath(
1458 node_to_append_from, neighbor, &path_between_nodes);
1461 auto* path_to_append =
new path_t();
1462 *path_to_append = current_path;
1463 *path_to_append += path_between_nodes;
1465 pool_of_paths->insert(path_to_append);
1471 template <
class GRAPH_T>
1476 using namespace std;
1479 typename std::map<mrpt::graphs::TNodeID, path_t*>::const_iterator search;
1480 search = m_node_optimal_paths.find(node);
1481 if (search != m_node_optimal_paths.end())
1483 path = search->second;
1491 template <
class GRAPH_T>
1494 path_t* path_between_nodes)
const 1498 using namespace std;
1501 this->m_graph->edgeExists(from, to) ||
1502 this->m_graph->edgeExists(to, from),
1504 "\nEdge between the provided nodeIDs" 1505 "(%lu <-> %lu) does not exist\n",
1512 path_between_nodes->
clear();
1516 double curr_determinant = 0;
1518 std::pair<edges_citerator, edges_citerator> fwd_edges_pair =
1519 this->m_graph->getEdges(from, to);
1528 for (
auto edges_it = fwd_edges_pair.first;
1529 edges_it != fwd_edges_pair.second; ++edges_it)
1534 curr_edge.copyFrom(edges_it->second);
1538 curr_edge.getInformationMatrix(inf_mat);
1543 curr_edge.cov_inv = inf_mat;
1554 *path_between_nodes = curr_path;
1558 std::pair<edges_citerator, edges_citerator> bwd_edges_pair =
1559 this->m_graph->getEdges(to, from);
1568 for (
auto edges_it = bwd_edges_pair.first;
1569 edges_it != bwd_edges_pair.second; ++edges_it)
1574 (edges_it->second).inverse(curr_edge);
1578 curr_edge.getInformationMatrix(inf_mat);
1583 curr_edge.cov_inv = inf_mat;
1594 *path_between_nodes = curr_path;
1601 template <
class GRAPH_T>
1603 typename std::set<path_t*>* pool_of_paths)
const 1606 using namespace std;
1609 path_t* optimal_path =
nullptr;
1610 double curr_determinant = 0;
1611 for (
auto it = pool_of_paths->begin(); it != pool_of_paths->end(); ++it)
1616 if (curr_determinant < (*it)->getDeterminant())
1624 pool_of_paths->erase(optimal_path);
1626 return optimal_path;
1630 template <
class GRAPH_T>
1637 using namespace std;
1642 this->m_graph->nodes.at(to) - this->m_graph->nodes.at(from);
1643 typename pose_t::vector_t mean_diff;
1644 (rel_edge.getMeanVal() - initial_estim).asVector(mean_diff);
1648 rel_edge.getCovariance(cov_mat);
1651 double mahal_distance =
1653 bool mahal_distance_null = std::isnan(mahal_distance);
1654 if (!mahal_distance_null)
1656 m_laser_params.mahal_distance_ICP_odom_win.addNewMeasurement(
1663 m_laser_params.mahal_distance_ICP_odom_win.getMedian() * 4;
1665 (threshold >= mahal_distance && !mahal_distance_null) ?
true :
false;
1677 template <
class GRAPH_T>
1682 this->registerNewEdge(hypot.from, hypot.to, hypot.getEdge());
1685 template <
class GRAPH_T>
1692 using namespace std;
1693 parent_t::registerNewEdge(from, to, rel_edge);
1696 m_edge_types_to_nums[
"ICP2D"]++;
1699 if (
absDiff(to, from) > m_lc_params.LC_min_nodeid_diff)
1701 m_edge_types_to_nums[
"LC"]++;
1702 this->m_just_inserted_lc =
true;
1707 this->m_just_inserted_lc =
false;
1711 this->m_graph->insertEdge(from, to, rel_edge);
1716 template <
class GRAPH_T>
1721 parent_t::setWindowManagerPtr(win_manager);
1724 if (this->m_win_manager)
1726 if (this->m_win_observer)
1728 this->m_win_observer->registerKeystroke(
1729 m_laser_params.keystroke_laser_scans,
1730 "Toggle LaserScans Visualization");
1731 this->m_win_observer->registerKeystroke(
1732 m_lc_params.keystroke_map_partitions,
1733 "Toggle Map Partitions Visualization");
1737 "Fetched the window manager, window observer successfully.");
1740 template <
class GRAPH_T>
1742 const std::map<std::string, bool>& events_occurred)
1745 parent_t::notifyOfWindowEvents(events_occurred);
1748 if (events_occurred.at(m_laser_params.keystroke_laser_scans))
1750 this->toggleLaserScansVisualization();
1753 if (events_occurred.at(m_lc_params.keystroke_map_partitions))
1755 this->toggleMapPartitionsVisualization();
1761 template <
class GRAPH_T>
1764 using namespace mrpt;
1770 this->m_win_manager->assignTextMessageParameters(
1771 &m_lc_params.offset_y_map_partitions,
1772 &m_lc_params.text_index_map_partitions);
1776 map_partitions_obj->setName(
"map_partitions");
1779 scene->insert(map_partitions_obj);
1780 this->m_win->unlockAccess3DScene();
1781 this->m_win->forceRepaint();
1784 template <
class GRAPH_T>
1787 using namespace mrpt;
1794 std::stringstream title;
1795 title <<
"# Partitions: " << m_curr_partitions.size();
1796 this->m_win_manager->addTextMessage(
1797 5, -m_lc_params.offset_y_map_partitions, title.str(),
1799 m_lc_params.text_index_map_partitions);
1810 map_partitions_obj = std::dynamic_pointer_cast<
CSetOfObjects>(obj);
1813 int partitionID = 0;
1814 bool partition_contains_last_node =
false;
1815 bool found_last_node =
1818 "Searching for the partition of the last nodeID: " 1819 << (this->m_graph->nodeCount() - 1));
1821 for (
auto p_it = m_curr_partitions.begin(); p_it != m_curr_partitions.end();
1822 ++p_it, ++partitionID)
1825 std::vector<uint32_t> nodes_list = *p_it;
1829 nodes_list.begin(), nodes_list.end(),
1830 this->m_graph->nodeCount() - 1) != nodes_list.end())
1832 partition_contains_last_node =
true;
1834 found_last_node =
true;
1838 partition_contains_last_node =
false;
1842 std::string partition_obj_name =
1844 std::string balloon_obj_name =
mrpt::format(
"#%d", partitionID);
1847 map_partitions_obj->getByName(partition_obj_name);
1854 curr_partition_obj = std::dynamic_pointer_cast<
CSetOfObjects>(obj);
1855 if (m_lc_params.LC_check_curr_partition_only)
1857 curr_partition_obj->setVisibility(partition_contains_last_node);
1863 "\tCreating a new CSetOfObjects partition object for partition " 1866 curr_partition_obj = std::make_shared<CSetOfObjects>();
1867 curr_partition_obj->setName(partition_obj_name);
1868 if (m_lc_params.LC_check_curr_partition_only)
1871 curr_partition_obj->setVisibility(partition_contains_last_node);
1876 CSphere::Ptr balloon_obj = std::make_shared<CSphere>();
1877 balloon_obj->setName(balloon_obj_name);
1878 balloon_obj->setRadius(m_lc_params.balloon_radius);
1879 balloon_obj->setColor_u8(m_lc_params.balloon_std_color);
1880 balloon_obj->enableShowName();
1882 curr_partition_obj->insert(balloon_obj);
1888 std::make_shared<CSetOfLines>();
1889 connecting_lines_obj->setName(
"connecting_lines");
1890 connecting_lines_obj->setColor_u8(
1891 m_lc_params.connecting_lines_color);
1892 connecting_lines_obj->setLineWidth(0.1f);
1894 curr_partition_obj->insert(connecting_lines_obj);
1899 map_partitions_obj->insert(curr_partition_obj);
1906 std::pair<double, double> centroid_coords;
1907 this->computeCentroidOfNodesVector(nodes_list, ¢roid_coords);
1910 centroid_coords.first, centroid_coords.second,
1911 m_lc_params.balloon_elevation);
1920 curr_partition_obj->getByName(balloon_obj_name);
1921 balloon_obj = std::dynamic_pointer_cast<
CSphere>(_obj);
1922 balloon_obj->setLocation(balloon_location);
1923 if (partition_contains_last_node)
1924 balloon_obj->setColor_u8(m_lc_params.balloon_curr_color);
1926 balloon_obj->setColor_u8(m_lc_params.balloon_std_color);
1939 curr_partition_obj->getByName(
"connecting_lines");
1940 connecting_lines_obj = std::dynamic_pointer_cast<
CSetOfLines>(_obj);
1942 connecting_lines_obj->clear();
1944 for (
auto it = nodes_list.begin(); it != nodes_list.end(); ++it)
1946 CPose3D curr_pose(this->m_graph->nodes.at(*it));
1947 TPoint3D curr_node_location(curr_pose.asTPose());
1950 curr_node_location, balloon_location);
1951 connecting_lines_obj->appendLine(connecting_line);
1957 if (!found_last_node)
1960 THROW_EXCEPTION(
"Last inserted nodeID was not found in any partition.");
1968 const size_t prev_size = m_last_partitions.size();
1969 const size_t curr_size = m_curr_partitions.size();
1970 if (curr_size < prev_size)
1973 for (
size_t pID = curr_size; pID != prev_size; ++pID)
1976 std::string partition_obj_name =
1977 mrpt::format(
"partition_%lu", static_cast<unsigned long>(pID));
1980 map_partitions_obj->getByName(partition_obj_name);
1984 "Partition: %s was not found", partition_obj_name.c_str());
1986 map_partitions_obj->removeObject(obj);
1991 this->m_win->unlockAccess3DScene();
1992 this->m_win->forceRepaint();
1995 template <
class GRAPH_T>
1999 ASSERTDEBMSG_(this->m_win,
"No CDisplayWindow3D* was provided");
2000 ASSERTDEBMSG_(this->m_win_manager,
"No CWindowManager* was provided");
2006 if (m_lc_params.visualize_map_partitions)
2009 scene->getByName(
"map_partitions");
2010 obj->setVisibility(!obj->isVisible());
2014 this->dumpVisibilityErrorMsg(
"visualize_map_partitions");
2017 this->m_win->unlockAccess3DScene();
2018 this->m_win->forceRepaint();
2023 template <
class GRAPH_T>
2025 const std::vector<uint32_t>& nodes_list,
2026 std::pair<double, double>* centroid_coords)
const 2032 double centroid_x = 0;
2033 double centroid_y = 0;
2034 for (
unsigned int node_it : nodes_list)
2036 pose_t curr_node_pos = this->m_graph->nodes.at(node_it);
2037 centroid_x += curr_node_pos.x();
2038 centroid_y += curr_node_pos.y();
2042 centroid_coords->first =
2043 centroid_x /
static_cast<double>(nodes_list.size());
2044 centroid_coords->second =
2045 centroid_y /
static_cast<double>(nodes_list.size());
2050 template <
class GRAPH_T>
2056 if (m_laser_params.visualize_laser_scans)
2059 this->m_win->get3DSceneAndLock();
2063 laser_scan_viz->enablePoints(
true);
2064 laser_scan_viz->enableLine(
true);
2065 laser_scan_viz->enableSurface(
true);
2066 laser_scan_viz->setSurfaceColor(
2067 m_laser_params.laser_scans_color.R,
2068 m_laser_params.laser_scans_color.G,
2069 m_laser_params.laser_scans_color.B,
2070 m_laser_params.laser_scans_color.A);
2072 laser_scan_viz->setName(
"laser_scan_viz");
2074 scene->insert(laser_scan_viz);
2075 this->m_win->unlockAccess3DScene();
2076 this->m_win->forceRepaint();
2082 template <
class GRAPH_T>
2088 if (m_laser_params.visualize_laser_scans && m_last_laser_scan2D)
2091 this->m_win->get3DSceneAndLock();
2094 scene->getByName(
"laser_scan_viz");
2097 laser_scan_viz->setScan(*m_last_laser_scan2D);
2101 this->m_graph->nodes.find(this->m_graph->nodeCount() - 1);
2102 if (search != this->m_graph->nodes.end())
2104 laser_scan_viz->setPose(search->second);
2108 laser_scan_viz->getPoseX(), laser_scan_viz->getPoseY(), -0.15,
2114 this->m_win->unlockAccess3DScene();
2115 this->m_win->forceRepaint();
2121 template <
class GRAPH_T>
2125 ASSERTDEBMSG_(this->m_win,
"No CDisplayWindow3D* was provided");
2126 ASSERTDEBMSG_(this->m_win_manager,
"No CWindowManager* was provided");
2132 if (m_laser_params.visualize_laser_scans)
2135 scene->getByName(
"laser_scan_viz");
2136 obj->setVisibility(!obj->isVisible());
2140 this->dumpVisibilityErrorMsg(
"visualize_laser_scans");
2143 this->m_win->unlockAccess3DScene();
2144 this->m_win->forceRepaint();
2149 template <
class GRAPH_T>
2151 std::map<std::string, int>* edge_types_to_num)
const 2154 *edge_types_to_num = m_edge_types_to_nums;
2158 template <
class GRAPH_T>
2162 parent_t::initializeVisuals();
2164 this->m_time_logger.enter(
"Visuals");
2167 m_laser_params.has_read_config,
2168 "Configuration parameters aren't loaded yet");
2169 if (m_laser_params.visualize_laser_scans)
2171 this->initLaserScansVisualization();
2173 if (m_lc_params.visualize_map_partitions)
2175 this->initMapPartitionsVisualization();
2178 if (m_visualize_curr_node_covariance)
2180 this->initCurrCovarianceVisualization();
2183 this->m_time_logger.leave(
"Visuals");
2186 template <
class GRAPH_T>
2190 parent_t::updateVisuals();
2192 this->m_time_logger.enter(
"Visuals");
2194 if (m_laser_params.visualize_laser_scans)
2196 this->updateLaserScansVisualization();
2198 if (m_lc_params.visualize_map_partitions)
2200 this->updateMapPartitionsVisualization();
2202 if (m_visualize_curr_node_covariance)
2204 this->updateCurrCovarianceVisualization();
2207 this->m_time_logger.leave(
"Visuals");
2211 template <
class GRAPH_T>
2215 using namespace std;
2219 this->m_win_manager->assignTextMessageParameters(
2220 &m_offset_y_curr_node_covariance, &m_text_index_curr_node_covariance);
2222 std::string title(
"Position uncertainty");
2223 this->m_win_manager->addTextMessage(
2224 5, -m_offset_y_curr_node_covariance, title,
2226 m_text_index_curr_node_covariance);
2230 cov_ellipsis_obj->setName(
"cov_ellipsis_obj");
2231 cov_ellipsis_obj->setColor_u8(m_curr_node_covariance_color);
2232 cov_ellipsis_obj->setLocation(0, 0, 0);
2236 scene->insert(cov_ellipsis_obj);
2237 this->m_win->unlockAccess3DScene();
2238 this->m_win->forceRepaint();
2243 template <
class GRAPH_T>
2247 using namespace std;
2254 path_t* path = queryOptimalPath(curr_node);
2259 pose_t curr_position = this->m_graph->nodes.at(curr_node);
2262 "In updateCurrCovarianceVisualization\n" 2263 "Covariance matrix:\n" 2275 cov_ellipsis_obj->setLocation(curr_position.x(), curr_position.y(), 0);
2278 cov_ellipsis_obj->setCovMatrix(mat);
2280 this->m_win->unlockAccess3DScene();
2281 this->m_win->forceRepaint();
2286 template <
class GRAPH_T>
2288 std::string viz_flag,
int sleep_time)
2294 "Cannot toggle visibility of specified object.\n " 2295 "Make sure that the corresponding visualization flag ( %s " 2296 ") is set to true in the .ini file.\n",
2298 std::this_thread::sleep_for(std::chrono::milliseconds(sleep_time));
2303 template <
class GRAPH_T>
2307 parent_t::loadParams(source_fname);
2309 m_partitioner.options.loadFromConfigFileName(
2310 source_fname,
"EdgeRegistrationDeciderParameters");
2311 m_laser_params.loadFromConfigFileName(
2312 source_fname,
"EdgeRegistrationDeciderParameters");
2313 m_lc_params.loadFromConfigFileName(
2314 source_fname,
"EdgeRegistrationDeciderParameters");
2318 m_consec_icp_constraint_factor = source.
read_double(
2319 "EdgeRegistrationDeciderParameters",
"consec_icp_constraint_factor",
2322 "EdgeRegistrationDeciderParameters",
"lc_icp_constraint_factor", 0.70,
2326 int min_verbosity_level = source.
read_int(
2327 "EdgeRegistrationDeciderParameters",
"class_verbosity", 1,
false);
2332 template <
class GRAPH_T>
2336 using namespace std;
2338 cout <<
"------------------[Pair-wise Consistency of ICP Edges - " 2339 "Registration Procedure Summary]------------------" 2342 parent_t::printParams();
2343 m_partitioner.options.dumpToConsole();
2344 m_laser_params.dumpToConsole();
2345 m_lc_params.dumpToConsole();
2347 cout <<
"Scan-matching ICP Constraint factor: " 2348 << m_consec_icp_constraint_factor << endl;
2349 cout <<
"Loop-closure ICP Constraint factor: " 2350 << m_lc_icp_constraint_factor << endl;
2356 template <
class GRAPH_T>
2358 std::string* report_str)
const 2363 std::stringstream class_props_ss;
2364 class_props_ss <<
"Pair-wise Consistency of ICP Edges - Registration " 2365 "Procedure Summary: " 2367 class_props_ss << this->header_sep << std::endl;
2370 const std::string time_res = this->m_time_logger.getStatsAsText();
2371 const std::string output_res = this->getLogAsString();
2374 report_str->clear();
2375 parent_t::getDescriptiveReport(report_str);
2377 *report_str += class_props_ss.str();
2378 *report_str += this->report_sep;
2380 *report_str += time_res;
2381 *report_str += this->report_sep;
2383 *report_str += output_res;
2384 *report_str += this->report_sep;
2389 template <
class GRAPH_T>
2393 partitions_out = this->getCurrentPartitions();
2396 template <
class GRAPH_T>
2397 const std::vector<std::vector<uint32_t>>&
2400 return m_curr_partitions;
2403 template <
class GRAPH_T>
2405 bool full_update,
bool is_first_time_node_reg)
2409 using namespace std;
2410 this->m_time_logger.enter(
"updateMapPartitions");
2417 "updateMapPartitions: Full partitioning of map was issued");
2420 m_partitioner.clear();
2421 nodes_to_scans = this->m_nodes_to_laser_scans2D;
2426 if (is_first_time_node_reg)
2428 nodes_to_scans.insert(make_pair(
2429 this->m_graph->root,
2430 this->m_nodes_to_laser_scans2D.at(this->m_graph->root)));
2434 nodes_to_scans.insert(make_pair(
2435 this->m_graph->nodeCount() - 1,
2436 this->m_nodes_to_laser_scans2D.at(this->m_graph->nodeCount() - 1)));
2442 for (
auto it = nodes_to_scans.begin(); it != nodes_to_scans.end(); ++it)
2447 "nodeID \"" << it->first <<
"\" has invalid laserScan");
2453 const auto& search = this->m_graph->nodes.find(it->first);
2454 if (search == this->m_graph->nodes.end())
2461 const auto curr_constraint =
constraint_t(search->second);
2469 m_partitioner.addMapFrame(sf, *pose3d);
2473 size_t curr_size = m_curr_partitions.size();
2474 m_last_partitions.resize(curr_size);
2475 for (
size_t i = 0; i < curr_size; i++)
2477 m_last_partitions[i] = m_curr_partitions[i];
2480 m_partitioner.updatePartitions(m_curr_partitions);
2483 this->m_time_logger.leave(
"updateMapPartitions");
2490 template <
class GRAPH_T>
2493 mahal_distance_ICP_odom_win.resizeWindow(
2495 goodness_threshold_win.resizeWindow(200);
2498 template <
class GRAPH_T>
2501 template <
class GRAPH_T>
2503 std::ostream&
out)
const 2507 out <<
"Use scan-matching constraints = " 2508 << (use_scan_matching ?
"TRUE" :
"FALSE") << std::endl;
2509 out <<
"Num. of previous nodes to check ICP against = " 2510 << prev_nodes_for_ICP << std::endl;
2511 out <<
"Visualize laser scans = " 2512 << (visualize_laser_scans ?
"TRUE" :
"FALSE") << std::endl;
2516 template <
class GRAPH_T>
2523 source.
read_bool(section,
"use_scan_matching",
true,
false);
2524 prev_nodes_for_ICP =
2526 section,
"prev_nodes_for_ICP", 10,
false);
2527 visualize_laser_scans = source.
read_bool(
2528 "VisualizationParameters",
"visualize_laser_scans",
true,
false);
2530 has_read_config =
true;
2536 template <
class GRAPH_T>
2538 : keystroke_map_partitions(
"b"),
2540 balloon_std_color(153, 0, 153),
2541 balloon_curr_color(62, 0, 80),
2542 connecting_lines_color(balloon_std_color)
2547 template <
class GRAPH_T>
2550 template <
class GRAPH_T>
2552 std::ostream&
out)
const 2555 using namespace std;
2558 ss <<
"Min. node difference for loop closure = " 2559 << LC_min_nodeid_diff << endl;
2560 ss <<
"Remote NodeIDs to consider the potential loop closure = " 2561 << LC_min_remote_nodes << endl;
2562 ss <<
"Min EigenValues ratio for accepting a hypotheses set = " 2563 << LC_eigenvalues_ratio_thresh << endl;
2564 ss <<
"Check only current node's partition for loop closures = " 2565 << (LC_check_curr_partition_only ?
"TRUE" :
"FALSE") << endl;
2566 ss <<
"New registered nodes required for full partitioning = " 2567 << full_partition_per_nodes << endl;
2568 ss <<
"Visualize map partitions = " 2569 << (visualize_map_partitions ?
"TRUE" :
"FALSE") << endl;
2575 template <
class GRAPH_T>
2580 LC_min_nodeid_diff = source.
read_int(
2581 "GeneralConfiguration",
"LC_min_nodeid_diff", 30,
false);
2582 LC_min_remote_nodes =
2583 source.
read_int(section,
"LC_min_remote_nodes", 3,
false);
2584 LC_eigenvalues_ratio_thresh =
2585 source.
read_double(section,
"LC_eigenvalues_ratio_thresh", 2,
false);
2586 LC_check_curr_partition_only =
2587 source.
read_bool(section,
"LC_check_curr_partition_only",
true,
false);
2588 full_partition_per_nodes =
2589 source.
read_int(section,
"full_partition_per_nodes", 50,
false);
2590 visualize_map_partitions = source.
read_bool(
2591 "VisualizationParameters",
"visualize_map_partitions",
true,
false);
2593 has_read_config =
true;
mrpt::obs::CObservation2DRangeScan::Ptr scan
void toggleMapPartitionsVisualization()
Toggle the map partitions visualization objects.
const partitions_t & getCurrentPartitions() const
bool eig(Derived &eVecs, std::vector< Scalar > &eVals, bool sorted=true) const
Computes the eigenvectors and eigenvalues for a square, general matrix.
GRAPH_T::global_pose_t pose
MAT_C::Scalar multiply_HtCH_scalar(const VECTOR_H &H, const MAT_C &C)
r (scalar) = H^t*C*H (H: column vector, C: symmetric matrix)
void insert(const CObservation::Ptr &obs)
Inserts a new observation to the list: The pointer to the objects is copied, thus DO NOT delete the p...
Holds the data of an information path.
std::vector< path_t > paths_t
#define MRPT_LOG_DEBUG(_STRING)
Use: MRPT_LOG_DEBUG("message");
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
VerbosityLevel
Enumeration of available verbosity levels.
const_iterator find(const KEY &key) const
A set of object, which are referenced to the coordinates framework established in this object...
#define THROW_EXCEPTION(msg)
void initMapPartitionsVisualization()
Initialize the visualization of the map partition objects.
std::string std::string format(std::string_view fmt, ARGS &&... args)
app setMinLoggingLevel(mrpt::system::LVL_ERROR)
static Ptr Create(Args &&... args)
typename GRAPH_T::constraint_t::type_value pose_t
typename GRAPH_T::global_pose_t global_pose_t
void updateCurrCovarianceVisualization()
void getMinUncertaintyPath(const mrpt::graphs::TNodeID from, const mrpt::graphs::TNodeID to, path_t *path) const
Given two nodeIDs compute and return the path connecting them.
This class allows loading and storing values and vectors of different types from ".ini" files easily.
void execDijkstraProjection(mrpt::graphs::TNodeID starting_node=0, mrpt::graphs::TNodeID ending_node=INVALID_NODEID)
compute the minimum uncertainty of each node position with regards to the graph root.
static CPose3DPDF * createFrom2D(const CPosePDF &o)
This is a static transformation method from 2D poses to 3D PDFs, preserving the representation type (...
size_type size() const
Get a 2-vector with [NROWS NCOLS] (as in MATLAB command size(x))
This file implements miscelaneous matrix and matrix/vector operations, and internal functions in mrpt...
double generatePWConsistencyElement(const mrpt::graphs::TNodeID &a1, const mrpt::graphs::TNodeID &a2, const mrpt::graphs::TNodeID &b1, const mrpt::graphs::TNodeID &b2, const hypotsp_t &hypots, const paths_t *opt_paths=nullptr)
Return the pair-wise consistency between the observations of the given nodes.
void splitPartitionToGroups(std::vector< uint32_t > &partition, std::vector< uint32_t > *groupA, std::vector< uint32_t > *groupB, int max_nodes_in_group=5)
Split an existing partition to Groups.
void getDescriptiveReport(std::string *report_str) const override
virtual bool getICPEdge(const mrpt::graphs::TNodeID &from, const mrpt::graphs::TNodeID &to, constraint_t *rel_edge, mrpt::slam::CICP::TReturnInfo *icp_info=nullptr, const TGetICPEdgeAdParams *ad_params=nullptr)
Get the ICP Edge between the provided nodes.
pose_t init_estim
Initial ICP estimation.
void updateVisuals() override
void setWindowManagerPtr(mrpt::graphslam::CWindowManager *win_manager) override
void computeCentroidOfNodesVector(const std::vector< uint32_t > &nodes_list, std::pair< double, double > *centroid_coords) const
Compute the Centroid of a group of a vector of node positions.
node_props_t from_params
Ad.
Struct for passing additional parameters to the getICPEdge call.
#define MRPT_LOG_WARN_STREAM(__CONTENTS)
void registerHypothesis(const hypot_t &h)
Wrapper around the registerNewEdge method which accepts a THypothesis object instead.
const mrpt::graphs::TNodeID & getDestination() const
Return the Destination node of this path.
void getAsString(std::string *str) const
void evaluatePartitionsForLC(const partitions_t &partitions)
Evaluate the given partitions for loop closures.
int read_int(const std::string §ion, const std::string &name, int defaultValue, bool failIfNotFound=false) const
bool computeDominantEigenVector(const mrpt::math::CMatrixDouble &consist_matrix, mrpt::math::CVectorDouble *eigvec, bool use_power_method=false)
std::vector< hypot_t * > hypotsp_t
void printParams() const override
static const path_t * findPathByEnds(const paths_t &vec_paths, const mrpt::graphs::TNodeID &src, const mrpt::graphs::TNodeID &dst, bool throw_exc=true)
Given a vector of TUncertaintyPath objects, find the one that has the given source and destination no...
CMatrixFixed< double, 3, 3 > CMatrixDouble33
SLAM methods related to graphs of pose constraints.
This class allows loading and storing values and vectors of different types from a configuration text...
This base provides a set of functions for maths stuff.
3D segment, consisting of two points.
bool mahalanobisDistanceOdometryToICPEdge(const mrpt::graphs::TNodeID &from, const mrpt::graphs::TNodeID &to, const constraint_t &rel_edge)
brief Compare the suggested ICP edge against the initial node difference.
#define MRPT_LOG_DEBUG_FMT(_FMT_STRING,...)
Use: MRPT_LOG_DEBUG_FMT("i=%u", i);
constraint_t curr_pose_pdf
Current path position + corresponding covariance.
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
constexpr double DEG2RAD(const double x)
Degrees to radians.
typename GRAPH_T::constraint_t constraint_t
This namespace contains representation of robot actions and observations.
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
This object renders a 2D laser scan by means of three elements: the points, the line along end-points...
Scalar det() const
Determinant of matrix.
double goodness
A goodness measure for the alignment, it is a [0,1] range indicator of percentage of correspondences...
double read_double(const std::string §ion, const std::string &name, double defaultValue, bool failIfNotFound=false) const
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
void generateHypotsPool(const std::vector< uint32_t > &groupA, const std::vector< uint32_t > &groupB, hypotsp_t *generated_hypots, const TGenerateHypotsPoolAdParams *ad_params=nullptr)
Generate the hypothesis pool for all the inter-group constraints between two groups of nodes...
#define MRPT_LOG_DEBUG_STREAM(__CONTENTS)
Use: MRPT_LOG_DEBUG_STREAM("Var=" << value << " foo=" << foo_var);
bool fillNodePropsFromGroupParams(const mrpt::graphs::TNodeID &nodeID, const std::map< mrpt::graphs::TNodeID, node_props_t > &group_params, node_props_t *node_props)
Fill the TNodeProps instance using the parameters from the map.
size_type rows() const
Number of rows in the matrix.
std::vector< std::vector< uint32_t > > partitions_t
size_type cols() const
Number of columns in the matrix.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
MAT::Scalar mahalanobisDistance2(const VECTORLIKE1 &X, const VECTORLIKE2 &MU, const MAT &COV)
Computes the squared mahalanobis distance of a vector X given the mean MU and the covariance inverse ...
void registerNewEdge(const mrpt::graphs::TNodeID &from, const mrpt::graphs::TNodeID &to, const constraint_t &rel_edge) override
void addToPath(const mrpt::graphs::TNodeID &node, const constraint_t &edge)
add a new link in the current path.
void evalPWConsistenciesMatrix(const mrpt::math::CMatrixDouble &consist_matrix, const hypotsp_t &hypots_pool, hypotsp_t *valid_hypots)
Evalute the consistencies matrix, fill the valid hypotheses.
return_t square(const num_t x)
Inline function for the square of a number.
#define ASSERTDEBMSG_(f, __ERROR_MSG)
typename parent_t::nodes_to_scans2D_t nodes_to_scans2D_t
A 3D ellipsoid, centered at zero with respect to this object pose.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
void addToPaths(std::set< path_t *> *pool_of_paths, const path_t &curr_path, const std::set< mrpt::graphs::TNodeID > &neibors) const
Append the paths starting from the current node.
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
static hypot_t * findHypotByEnds(const hypotsp_t &vec_hypots, const mrpt::graphs::TNodeID &from, const mrpt::graphs::TNodeID &to, bool throw_exc=true)
Given a vector of THypothesis objects, find the one that has the given start and end nodes...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
mrpt::vision::TStereoCalibResults out
void generatePWConsistenciesMatrix(const std::vector< uint32_t > &groupA, const std::vector< uint32_t > &groupB, const hypotsp_t &hypots_pool, mrpt::math::CMatrixDouble *consist_matrix, const paths_t *groupA_opt_paths=nullptr, const paths_t *groupB_opt_paths=nullptr)
Compute the pair-wise consistencies Matrix.
static hypot_t * findHypotByID(const hypotsp_t &vec_hypots, size_t id, bool throw_exc=true)
Given a vector of THypothesis objects, find the one that has the given ID.
#define ASSERTDEB_(f)
Defines an assertion mechanism - only when compiled in debug.
node_props_t to_params
Ad.
bool read_bool(const std::string §ion, const std::string &name, bool defaultValue, bool failIfNotFound=false) const
void updateLaserScansVisualization()
void notifyOfWindowEvents(const std::map< std::string, bool > &events_occurred) override
matrix_size_t size() const
Get a 2-vector with [NROWS NCOLS] (as in MATLAB command size(x))
A solid or wire-frame sphere.
void checkPartitionsForLC(partitions_t *partitions_for_LC)
Check the registered so far partitions for potential loop closures.
An RGBA color - floats in the range [0,1].
void loadParams(const std::string &source_fname) override
Struct for passing additional parameters to the generateHypotsPool call.
The ICP algorithm return information.
virtual void fetchNodeIDsForScanMatching(const mrpt::graphs::TNodeID &curr_nodeID, std::set< mrpt::graphs::TNodeID > *nodes_set)
Fetch a list of nodes with regards prior to the given nodeID for which to try and add scan matching e...
The namespace for 3D scene representation and rendering.
void toggleLaserScansVisualization()
togle the LaserScans visualization on and off
void updateMapPartitions(bool full_update=false, bool is_first_time_node_reg=false)
Split the currently registered graph nodes into partitions.
uint64_t TNodeID
A generic numeric type for unique IDs of nodes or entities.
void initializeVisuals() override
bool updateState(mrpt::obs::CActionCollection::Ptr action, mrpt::obs::CSensoryFrame::Ptr observations, mrpt::obs::CObservation::Ptr observation) override
Classes for creating GUI windows for 2D and 3D visualization.
T absDiff(const T &lhs, const T &rhs)
Absolute difference between two numbers.
~TLoopClosureParams() override
mrpt::graphslam::TUncertaintyPath< GRAPH_T > * popMinUncertaintyPath(std::set< path_t *> *pool_of_paths) const
Find the minimum uncertainty path from te given pool of TUncertaintyPath instances.
void initCurrCovarianceVisualization()
void updateMapPartitionsVisualization()
Update the map partitions visualization.
EIGEN_MAP asEigen()
Get as an Eigen-compatible Eigen::Map object.
void initLaserScansVisualization()
std::vector< mrpt::graphs::TNodeID > nodes_traversed
Nodes that the Path comprises of.
An edge hypothesis between two nodeIDs.
void assertIsBetweenNodeIDs(const mrpt::graphs::TNodeID &from, const mrpt::graphs::TNodeID &to) const
Assert that the current path is between the given nodeIDs.
A set of independent lines (or segments), one line with its own start and end positions (X...
void dumpVisibilityErrorMsg(std::string viz_flag, int sleep_time=500)
#define THROW_EXCEPTION_FMT(_FORMAT_STRING,...)
#define MRPT_LOG_ERROR_STREAM(__CONTENTS)
mrpt::graphslam::TUncertaintyPath< GRAPH_T > * queryOptimalPath(const mrpt::graphs::TNodeID node) const
Query for the optimal path of a nodeID.
Internal auxiliary classes.
std::string getSTLContainerAsString(const T &t)
Return a STL container in std::string form.
bool getPropsOfNodeID(const mrpt::graphs::TNodeID &nodeID, global_pose_t *pose, mrpt::obs::CObservation2DRangeScan::Ptr &scan, const node_props_t *node_props=nullptr) const
Fill the pose and LaserScan for the given nodeID.
void getEdgesStats(std::map< std::string, int > *edge_types_to_num) const override
typename mrpt::graphs::detail::THypothesis< GRAPH_T > hypot_t
Class acts as a container for storing pointers to mrpt::gui::CDisplayWindow3D, mrpt::graphslam::CWind...
bool approximatelyEqual(T1 a, T1 b, T2 epsilon)
Compare 2 floats and determine whether they are equal.
virtual void addScanMatchingEdges(const mrpt::graphs::TNodeID &curr_nodeID)
Addd ICP constraints from X previous nodeIDs up to the given nodeID.
#define MRPT_LOG_INFO(_STRING)
~CLoopCloserERD() override
#define MRPT_UNUSED_PARAM(a)
Determines whether this is an X86 or AMD64 platform.