10 #ifndef CLOOPCLOSERERD_IMPL_H 11 #define CLOOPCLOSERERD_IMPL_H 22 template <
class GRAPH_T>
24 : m_visualize_curr_node_covariance(false),
25 m_curr_node_covariance_color(160, 160, 160, 255),
26 m_partitions_full_update(false),
27 m_is_first_time_node_reg(true),
28 m_dijkstra_node_count_thresh(3)
30 this->initializeLoggers(
"CLoopCloserERD");
36 template <
class GRAPH_T>
44 m_node_optimal_paths.begin();
45 it != m_node_optimal_paths.end(); ++it)
54 template <
class GRAPH_T>
62 this->m_time_logger.enter(
"updateState");
74 getObservation<CObservation2DRangeScan>(observations, observation);
77 m_last_laser_scan2D = scan;
81 if (!m_first_laser_scan)
83 m_first_laser_scan = m_last_laser_scan2D;
87 size_t num_registered =
88 absDiff(this->m_last_total_num_nodes, this->m_graph->nodeCount());
89 bool registered_new_node = num_registered > 0;
91 if (registered_new_node)
94 registered_new_node =
true;
98 if (!this->m_override_registered_nodes_check)
100 if (!((num_registered == 1) ^
101 (num_registered == 2 && m_is_first_time_node_reg)))
104 "Invalid number of registered nodes since last call to " 107 << num_registered <<
"\" new nodes.");
118 if (m_is_first_time_node_reg)
121 "Assigning first laserScan to the graph root node.");
122 this->m_nodes_to_laser_scans2D[this->m_graph->root] =
124 m_is_first_time_node_reg =
false;
128 this->m_nodes_to_laser_scans2D[this->m_graph->nodeCount() - 1] =
131 if (m_laser_params.use_scan_matching)
134 this->addScanMatchingEdges(this->m_graph->nodeCount() - 1);
138 m_partitions_full_update =
139 ((this->m_graph->nodeCount() %
140 m_lc_params.full_partition_per_nodes) == 0 ||
141 this->m_just_inserted_lc)
145 this->updateMapPartitions(
146 m_partitions_full_update,
147 num_registered == 2);
151 this->checkPartitionsForLC(&partitions_for_LC);
152 this->evaluatePartitionsForLC(partitions_for_LC);
154 if (m_visualize_curr_node_covariance)
156 this->execDijkstraProjection();
159 this->m_last_total_num_nodes = this->m_graph->nodeCount();
162 this->m_time_logger.leave(
"updateState");
167 template <
class GRAPH_T>
170 std::set<mrpt::utils::TNodeID>* nodes_set)
176 int fetched_nodeIDs = 0;
177 for (
int nodeID_i = static_cast<int>(curr_nodeID) - 1;
178 ((fetched_nodeIDs <= this->m_laser_params.prev_nodes_for_ICP) &&
183 nodes_set->insert(nodeID_i);
188 template <
class GRAPH_T>
194 using namespace mrpt;
202 std::set<TNodeID> nodes_set;
203 this->fetchNodeIDsForScanMatching(curr_nodeID, &nodes_set);
207 node_it != nodes_set.end(); ++node_it)
213 "Fetching laser scan for nodes: " << *node_it <<
"==> " 217 this->getICPEdge(*node_it, curr_nodeID, &rel_edge, &icp_info);
218 if (!found_edge)
continue;
225 m_laser_params.goodness_threshold_win.addNewMeasurement(
228 double goodness_thresh =
229 m_laser_params.goodness_threshold_win.getMedian() *
230 m_consec_icp_constraint_factor;
231 bool accept_goodness = icp_info.
goodness > goodness_thresh;
233 "Curr. Goodness: " << icp_info.
goodness 234 <<
"|\t Threshold: " << goodness_thresh <<
" => " 235 << (accept_goodness ?
"ACCEPT" :
"REJECT"));
239 bool accept_mahal_distance = this->mahalanobisDistanceOdometryToICPEdge(
240 *node_it, curr_nodeID, rel_edge);
243 if (accept_goodness && accept_mahal_distance)
245 this->registerNewEdge(*node_it, curr_nodeID, rel_edge);
251 template <
class GRAPH_T>
259 this->m_time_logger.enter(
"getICPEdge");
277 "TGetICPEdgeAdParams:\n" 284 bool from_success = this->getPropsOfNodeID(
285 from, &from_pose, from_scan, from_params);
288 bool to_success = this->getPropsOfNodeID(to, &to_pose, to_scan, to_params);
290 if (!from_success || !to_success)
294 << from <<
" or node #" << to
295 <<
" doesn't contain a valid LaserScan. Ignoring this...");
308 initial_estim = to_pose - from_pose;
312 "from_pose: " << from_pose <<
"| to_pose: " << to_pose
313 <<
"| init_estim: " << initial_estim);
315 range_ops_t::getICPEdge(
316 *from_scan, *to_scan, rel_edge, &initial_estim, icp_info);
319 this->m_time_logger.leave(
"getICPEdge");
324 template <
class GRAPH_T>
327 const std::map<mrpt::utils::TNodeID, node_props_t>& group_params,
339 search = group_params.find(nodeID);
341 if (search == group_params.end())
347 *node_props = search->second;
357 template <
class GRAPH_T>
366 bool filled_pose =
false;
367 bool filled_scan =
false;
374 *pose = node_props->
pose;
378 if (node_props->
scan)
380 scan = node_props->
scan;
387 !(filled_pose ^ filled_scan),
389 "Either BOTH or NONE of the filled_pose, filled_scan should be set." 391 static_cast<unsigned long>(nodeID)));
400 this->m_graph->nodes.find(nodeID);
401 if (search != this->m_graph->nodes.end())
403 *pose = search->second;
414 this->m_nodes_to_laser_scans2D.find(nodeID);
415 if (search != this->m_nodes_to_laser_scans2D.end())
417 scan = search->second;
422 return filled_pose && filled_scan;
425 template <
class GRAPH_T>
430 this->m_time_logger.enter(
"LoopClosureEvaluation");
433 using namespace mrpt;
437 partitions_for_LC->clear();
443 if (m_partitions_full_update)
445 m_partitionID_to_prev_nodes_list.clear();
451 partitions_it != m_curr_partitions.end();
452 ++partitions_it, ++partitionID)
456 if (m_lc_params.LC_check_curr_partition_only)
458 bool curr_node_in_curr_partition =
460 partitions_it->begin(), partitions_it->end(),
461 this->m_graph->nodeCount() - 1)) != partitions_it->end());
462 if (!curr_node_in_curr_partition)
469 finder = m_partitionID_to_prev_nodes_list.find(partitionID);
470 if (finder == m_partitionID_to_prev_nodes_list.end())
473 m_partitionID_to_prev_nodes_list.insert(
474 make_pair(partitionID, *partitions_it));
478 if (*partitions_it == finder->second)
488 finder->second = *partitions_it;
493 int curr_node_index = 1;
494 size_t prev_nodeID = *(partitions_it->begin());
496 it != partitions_it->end(); ++it, ++curr_node_index)
498 size_t curr_nodeID = *it;
502 if ((curr_nodeID - prev_nodeID) > m_lc_params.LC_min_nodeid_diff)
506 int num_after_nodes = partitions_it->size() - curr_node_index;
507 int num_before_nodes = partitions_it->size() - num_after_nodes;
508 if (num_after_nodes >= m_lc_params.LC_min_remote_nodes &&
509 num_before_nodes >= m_lc_params.LC_min_remote_nodes)
512 "Found potential loop closures:" 514 <<
"\tPartitionID: " << partitionID << endl
518 <<
"\t" << prev_nodeID <<
" ==> " << curr_nodeID << endl
519 <<
"\tNumber of LC nodes: " << num_after_nodes);
520 partitions_for_LC->push_back(*partitions_it);
527 prev_nodeID = curr_nodeID;
530 LVL_DEBUG,
"Successfully checked partition: %d", partitionID);
533 this->m_time_logger.leave(
"LoopClosureEvaluation");
537 template <
class GRAPH_T>
542 using namespace mrpt;
547 this->m_time_logger.enter(
"LoopClosureEvaluation");
549 if (partitions.size() == 0)
return;
552 LVL_DEBUG,
"Evaluating partitions for loop closures...\n%s\n",
553 this->header_sep.c_str());
557 p_it != partitions.end(); ++p_it)
563 this->splitPartitionToGroups(
564 partition, &groupA, &groupB,
569 this->generateHypotsPool(groupA, groupB, &hypots_pool);
572 CMatrixDouble consist_matrix(hypots_pool.size(), hypots_pool.size());
573 this->generatePWConsistenciesMatrix(
574 groupA, groupB, hypots_pool, &consist_matrix);
578 this->evalPWConsistenciesMatrix(
579 consist_matrix, hypots_pool, &valid_hypots);
582 if (valid_hypots.size())
586 it != valid_hypots.end(); ++it)
588 this->registerHypothesis(**it);
594 it != hypots_pool.end(); ++it)
601 this->m_time_logger.leave(
"LoopClosureEvaluation");
606 template <
class GRAPH_T>
617 valid_hypots->clear();
622 bool valid_lambda_ratio = this->computeDominantEigenVector(
625 if (!valid_lambda_ratio)
return;
633 double dot_product = 0;
634 for (
int i = 0; i !=
w.size(); ++i)
641 double potential_dot_product =
642 ((
w.transpose() * u) /
w.squaredNorm()).
value();
644 "current: %f | potential_dot_product: %f", dot_product,
645 potential_dot_product);
646 if (potential_dot_product > dot_product)
649 dot_product = potential_dot_product;
659 cout <<
"Outcome of discretization: " <<
w.transpose() << endl;
665 for (
int wi = 0; wi !=
w.size(); ++wi)
672 valid_hypots->push_back(this->findHypotByID(hypots_pool, wi));
681 template <
class GRAPH_T>
684 int max_nodes_in_group )
688 using namespace mrpt;
693 ASSERTMSG_(groupA,
"Pointer to groupA is not valid");
694 ASSERTMSG_(groupB,
"Pointer to groupB is not valid");
696 max_nodes_in_group == -1 || max_nodes_in_group > 0,
698 "Value %d not permitted for max_nodes_in_group" 699 "Either use a positive integer, " 700 "or -1 for non-restrictive partition size",
701 max_nodes_in_group));
706 size_t index_to_split = 1;
708 it != partition.end(); ++it, ++index_to_split)
712 if ((curr_nodeID - prev_nodeID) > m_lc_params.LC_min_nodeid_diff)
717 prev_nodeID = curr_nodeID;
719 ASSERT_(partition.size() > index_to_split);
723 vector_uint(partition.begin(), partition.begin() + index_to_split);
724 *groupB =
vector_uint(partition.begin() + index_to_split, partition.end());
726 if (max_nodes_in_group != -1)
729 if (groupA->size() >
static_cast<size_t>(max_nodes_in_group))
732 groupA->begin(), groupA->begin() + max_nodes_in_group);
735 if (groupB->size() >
static_cast<size_t>(max_nodes_in_group))
738 vector_uint(groupB->end() - max_nodes_in_group, groupB->end());
746 template <
class GRAPH_T>
754 using namespace mrpt;
758 "generateHypotsPool: Given hypotsp_t pointer is invalid.");
759 generated_hypots->clear();
764 <<
" - size: " << groupA.size() << endl);
767 <<
" - size: " << groupB.size() << endl);
780 size_t nodes_count = groupA.size();
784 nodes_count ==
params.size(),
786 "Size mismatch between nodeIDs in group [%lu]" 787 " and corresponding properties map [%lu]",
788 nodes_count,
params.size()));
794 int hypot_counter = 0;
795 int invalid_hypots = 0;
799 b_it = groupB.begin();
800 b_it != groupB.end(); ++b_it)
803 a_it = groupA.begin();
804 a_it != groupA.end(); ++a_it)
813 hypot->
id = hypot_counter++;
828 fillNodePropsFromGroupParams(
832 fillNodePropsFromGroupParams(
854 bool found_edge = this->getICPEdge(
855 *b_it, *a_it, &edge, &icp_info, icp_ad_params);
864 double goodness_thresh =
865 m_laser_params.goodness_threshold_win.getMedian() *
866 m_lc_icp_constraint_factor;
867 bool accept_goodness = icp_info.
goodness > goodness_thresh;
869 "generateHypotsPool:\nCurr. Goodness: " 870 << icp_info.
goodness <<
"|\t Threshold: " << goodness_thresh
871 <<
" => " << (accept_goodness ?
"ACCEPT" :
"REJECT")
874 if (!found_edge || !accept_goodness)
879 generated_hypots->push_back(hypot);
885 delete icp_ad_params;
889 "Generated pool of hypotheses...\tsize = " 890 << generated_hypots->size()
891 <<
"\tinvalid hypotheses: " << invalid_hypots);
898 template <
class GRAPH_T>
904 using namespace mrpt;
910 this->m_time_logger.enter(
"DominantEigenvectorComputation");
912 double lambda1, lambda2;
913 bool is_valid_lambda_ratio =
false;
915 if (use_power_method)
918 "\nPower method for computing the first two " 919 "eigenvectors/eigenvalues hasn't been implemented yet\n");
924 consist_matrix.eigenVectors(eigvecs, eigvals);
930 eigvecs.size() == eigvals.size() &&
931 consist_matrix.size() == eigvals.size(),
933 "Size of eigvecs \"%lu\"," 935 "consist_matrix \"%lu\" don't match",
936 static_cast<unsigned long>(eigvecs.size()),
937 static_cast<unsigned long>(eigvals.size()),
938 static_cast<unsigned long>(consist_matrix.size())));
940 eigvecs.extractCol(eigvecs.getColCount() - 1, *eigvec);
941 lambda1 = eigvals(eigvals.getRowCount() - 1, eigvals.getColCount() - 1);
942 lambda2 = eigvals(eigvals.getRowCount() - 2, eigvals.getColCount() - 2);
946 for (
int i = 0; i != eigvec->size(); ++i)
948 (*eigvec)(i) = abs((*eigvec)(i));
956 "Bad lambda2 value: " 957 << lambda2 <<
" => Skipping current evaluation." << endl);
960 double curr_lambda_ratio = lambda1 / lambda2;
962 "lambda1 = " << lambda1 <<
" | lambda2 = " << lambda2
963 <<
"| ratio = " << curr_lambda_ratio << endl);
965 is_valid_lambda_ratio =
966 (curr_lambda_ratio > m_lc_params.LC_eigenvalues_ratio_thresh);
968 this->m_time_logger.leave(
"DominantEigenvectorComputation");
969 return is_valid_lambda_ratio;
974 template <
class GRAPH_T>
978 const paths_t* groupA_opt_paths ,
979 const paths_t* groupB_opt_paths )
983 using namespace mrpt;
988 consist_matrix,
"Invalid pointer to the Consistency matrix is given");
990 static_cast<unsigned long>(consist_matrix->rows()) ==
991 hypots_pool.size() &&
992 static_cast<unsigned long>(consist_matrix->rows()) ==
994 "Consistency matrix dimensions aren't equal to the hypotheses pool " 998 ">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>" 1000 <<
"In generatePWConsistencyMatrix:\n" 1003 <<
"\tHypots pool Size: " << hypots_pool.size());
1007 b1_it != groupB.end(); ++b1_it)
1013 b2_it != groupB.end(); ++b2_it)
1019 a1_it != groupA.end(); ++a1_it)
1023 this->findHypotByEnds(hypots_pool,
b2,
a1);
1029 a2_it != groupA.end(); ++a2_it)
1033 this->findHypotByEnds(hypots_pool,
b1,
a2);
1046 extracted_hypots.push_back(hypot_b2_a1);
1047 extracted_hypots.push_back(hypot_b1_a2);
1049 paths_t* curr_opt_paths = NULL;
1050 if (groupA_opt_paths || groupB_opt_paths)
1052 curr_opt_paths =
new paths_t();
1059 if (groupA_opt_paths)
1061 const path_t*
p = this->findPathByEnds(
1062 *groupA_opt_paths,
a1,
a2,
1064 curr_opt_paths->push_back(*
p);
1068 curr_opt_paths->push_back(
path_t());
1071 if (groupB_opt_paths)
1073 const path_t*
p = this->findPathByEnds(
1074 *groupB_opt_paths,
b1,
b2,
1076 curr_opt_paths->push_back(*
p);
1080 curr_opt_paths->push_back(
path_t());
1084 consistency = this->generatePWConsistencyElement(
1085 a1,
a2,
b1,
b2, extracted_hypots, curr_opt_paths);
1087 delete curr_opt_paths;
1102 int id1 = hypot_b2_a1->
id;
1103 int id2 = hypot_b1_a2->
id;
1105 (*consist_matrix)(id1, id2) = consistency;
1106 (*consist_matrix)(id2, id1) = consistency;
1123 template <
class GRAPH_T>
1130 using namespace std;
1131 using namespace mrpt;
1153 ASSERT_(opt_paths->size() == 2);
1160 const path_t* path_a1_a2;
1161 if (!opt_paths || opt_paths->begin()->isEmpty())
1164 "Running dijkstra [a1] " <<
a1 <<
" => [a2] " <<
a2);
1165 execDijkstraProjection(
a1,
a2);
1166 path_a1_a2 = this->queryOptimalPath(
a2);
1171 path_a1_a2 = &(*opt_paths->begin());
1177 const path_t* path_b1_b2;
1178 if (!opt_paths || opt_paths->rend()->isEmpty())
1181 "Running djkstra [b1] " <<
b1 <<
" => [b2] " <<
b2);
1182 execDijkstraProjection(
b1,
b2);
1183 path_b1_b2 = this->queryOptimalPath(
b2);
1187 path_b1_b2 = &(*opt_paths->rbegin());
1195 hypot_t* hypot_b1_a2 = this->findHypotByEnds(hypots,
b1,
a2);
1197 hypot_t* hypot_b2_a1 = this->findHypotByEnds(hypots,
b2,
a1);
1204 res_transform += hypot_b2_a1->
getEdge();
1207 "\n-----------Resulting Transformation----------- Hypots: #" 1208 << hypot_b1_a2->
id <<
", #" << hypot_b2_a1->
id << endl
1209 <<
"a1 --> a2 => b1 --> b2 => a1: " <<
a1 <<
" --> " <<
a2 <<
" => " 1210 <<
b1 <<
" --> " <<
b2 <<
" => " <<
a1 << endl
1211 << res_transform << endl
1213 <<
"DIJKSTRA: " <<
a1 <<
" --> " <<
a2 <<
": " 1215 <<
"DIJKSTRA: " <<
b1 <<
" --> " <<
b2 <<
": " 1217 <<
"hypot_b1_a2(inv):\n" 1220 << hypot_b2_a1->
getEdge() << endl);
1224 res_transform.getMeanVal().getAsVector(T);
1228 res_transform.getCovariance(cov_mat);
1234 double exponent = (-T.transpose() * cov_mat * T).
value();
1235 double consistency_elem = exp(exponent);
1242 return consistency_elem;
1246 template <
class GRAPH_T>
1252 using namespace mrpt;
1258 cit != vec_paths.end(); ++cit)
1260 if (cit->getSource() ==
src && cit->getDestination() ==
dst)
1266 if (throw_exc && !
res)
1270 "Path for %lu => %lu is not found. Exiting...\n",
1271 static_cast<unsigned long>(
src),
1272 static_cast<unsigned long>(
dst)));
1278 template <
class GRAPH_T>
1285 using namespace std;
1288 v_cit != vec_hypots.end(); v_cit++)
1290 if ((*v_cit)->hasEnds(from, to))
1309 template <
class GRAPH_T>
1312 const hypotsp_t& vec_hypots,
const size_t&
id,
bool throw_exc )
1317 v_cit != vec_hypots.end(); v_cit++)
1319 if ((*v_cit)->id ==
id)
1336 template <
class GRAPH_T>
1342 using namespace std;
1343 using namespace mrpt;
1351 this->m_time_logger.enter(
"Dijkstra Projection");
1353 "----------- Done with Dijkstra Projection... ----------";
1359 (ending_node >= 0 && ending_node < this->m_graph->nodeCount()));
1361 starting_node != ending_node,
"Starting and Ending nodes coincede");
1364 stringstream ss_debug(
"");
1365 ss_debug <<
"Executing Dijkstra Projection: " << starting_node <<
" => ";
1368 ss_debug <<
"..." << endl;
1372 ss_debug << ending_node << endl;
1375 if (this->m_graph->nodeCount() < m_dijkstra_node_count_thresh)
1381 std::vector<bool> visited_nodes(this->m_graph->nodeCount(),
false);
1382 m_node_optimal_paths.clear();
1385 std::map<TNodeID, std::set<TNodeID>> neighbors_of;
1386 this->m_graph->getAdjacencyMatrix(neighbors_of);
1391 std::set<path_t*> pool_of_paths;
1393 std::set<TNodeID> starting_node_neighbors(neighbors_of.at(starting_node));
1395 starting_node_neighbors.begin();
1396 n_it != starting_node_neighbors.end(); ++n_it)
1399 this->getMinUncertaintyPath(
1400 starting_node, *n_it, path_between_neighbors);
1402 pool_of_paths.insert(path_between_neighbors);
1405 visited_nodes.at(starting_node) =
true;
1423 it != visited_nodes.end(); ++it)
1436 if (visited_nodes.at(ending_node))
1439 this->m_time_logger.leave(
"Dijkstra Projection");
1444 path_t* optimal_path = this->popMinUncertaintyPath(&pool_of_paths);
1469 if (!visited_nodes.at(dest))
1471 m_node_optimal_paths[dest] = optimal_path;
1472 visited_nodes.at(dest) =
true;
1478 &pool_of_paths, *optimal_path, neighbors_of.at(dest));
1483 this->m_time_logger.leave(
"Dijkstra Projection");
1487 template <
class GRAPH_T>
1489 std::set<path_t*>* pool_of_paths,
const path_t& current_path,
1490 const std::set<mrpt::utils::TNodeID>& neighbors)
const 1494 using namespace std;
1505 neigh_it != neighbors.end(); ++neigh_it)
1507 if (*neigh_it == second_to_last_node)
continue;
1510 path_t path_between_nodes;
1511 this->getMinUncertaintyPath(
1512 node_to_append_from, *neigh_it, &path_between_nodes);
1516 *path_to_append = current_path;
1517 *path_to_append += path_between_nodes;
1519 pool_of_paths->insert(path_to_append);
1525 template <
class GRAPH_T>
1529 using namespace std;
1533 search = m_node_optimal_paths.find(node);
1534 if (search != m_node_optimal_paths.end())
1536 path = search->second;
1544 template <
class GRAPH_T>
1547 path_t* path_between_nodes)
const 1552 using namespace std;
1555 this->m_graph->edgeExists(from, to) ||
1556 this->m_graph->edgeExists(to, from),
1558 "\nEdge between the provided nodeIDs" 1559 "(%lu <-> %lu) does not exist\n",
1566 path_between_nodes->
clear();
1570 double curr_determinant = 0;
1572 std::pair<edges_citerator, edges_citerator> fwd_edges_pair =
1573 this->m_graph->getEdges(from, to);
1583 edges_it != fwd_edges_pair.second; ++edges_it)
1588 curr_edge.copyFrom(edges_it->second);
1592 curr_edge.getInformationMatrix(inf_mat);
1597 curr_edge.cov_inv = inf_mat;
1608 *path_between_nodes = curr_path;
1612 std::pair<edges_citerator, edges_citerator> bwd_edges_pair =
1613 this->m_graph->getEdges(to, from);
1623 edges_it != bwd_edges_pair.second; ++edges_it)
1628 (edges_it->second).
inverse(curr_edge);
1632 curr_edge.getInformationMatrix(inf_mat);
1637 curr_edge.cov_inv = inf_mat;
1648 *path_between_nodes = curr_path;
1655 template <
class GRAPH_T>
1657 typename std::set<path_t*>* pool_of_paths)
const 1660 using namespace std;
1663 path_t* optimal_path = NULL;
1664 double curr_determinant = 0;
1666 it != pool_of_paths->end(); ++it)
1671 if (curr_determinant < (*it)->getDeterminant())
1679 pool_of_paths->erase(optimal_path);
1681 return optimal_path;
1685 template <
class GRAPH_T>
1692 using namespace std;
1698 this->m_graph->nodes.at(to) - this->m_graph->nodes.at(from);
1700 (rel_edge.getMeanVal() - initial_estim).getAsVector(mean_diff);
1704 rel_edge.getCovariance(cov_mat);
1707 double mahal_distance =
1709 bool mahal_distance_null = std::isnan(mahal_distance);
1710 if (!mahal_distance_null)
1712 m_laser_params.mahal_distance_ICP_odom_win.addNewMeasurement(
1719 m_laser_params.mahal_distance_ICP_odom_win.getMedian() * 4;
1721 (threshold >= mahal_distance && !mahal_distance_null) ?
true :
false;
1733 template <
class GRAPH_T>
1738 this->registerNewEdge(hypot.
from, hypot.
to, hypot.
getEdge());
1741 template <
class GRAPH_T>
1749 using namespace std;
1750 parent_t::registerNewEdge(from, to, rel_edge);
1753 m_edge_types_to_nums[
"ICP2D"]++;
1756 if (
absDiff(to, from) > m_lc_params.LC_min_nodeid_diff)
1758 m_edge_types_to_nums[
"LC"]++;
1759 this->m_just_inserted_lc =
true;
1760 this->logFmt(LVL_INFO,
"\tLoop Closure edge!");
1764 this->m_just_inserted_lc =
false;
1768 this->m_graph->insertEdge(from, to, rel_edge);
1773 template <
class GRAPH_T>
1778 parent_t::setWindowManagerPtr(win_manager);
1783 if (this->m_win_manager)
1785 if (this->m_win_observer)
1787 this->m_win_observer->registerKeystroke(
1788 m_laser_params.keystroke_laser_scans,
1789 "Toggle LaserScans Visualization");
1790 this->m_win_observer->registerKeystroke(
1791 m_lc_params.keystroke_map_partitions,
1792 "Toggle Map Partitions Visualization");
1797 "Fetched the window manager, window observer successfully.");
1800 template <
class GRAPH_T>
1802 const std::map<std::string, bool>& events_occurred)
1805 parent_t::notifyOfWindowEvents(events_occurred);
1808 if (events_occurred.at(m_laser_params.keystroke_laser_scans))
1810 this->toggleLaserScansVisualization();
1813 if (events_occurred.at(m_lc_params.keystroke_map_partitions))
1815 this->toggleMapPartitionsVisualization();
1821 template <
class GRAPH_T>
1824 using namespace mrpt;
1830 if (!m_lc_params.LC_check_curr_partition_only)
1832 this->m_win_manager->assignTextMessageParameters(
1833 &m_lc_params.offset_y_map_partitions,
1834 &m_lc_params.text_index_map_partitions);
1839 mrpt::make_aligned_shared<CSetOfObjects>();
1840 map_partitions_obj->setName(
"map_partitions");
1843 scene->insert(map_partitions_obj);
1844 this->m_win->unlockAccess3DScene();
1845 this->m_win->forceRepaint();
1848 template <
class GRAPH_T>
1851 using namespace mrpt;
1859 if (!m_lc_params.LC_check_curr_partition_only)
1861 std::stringstream title;
1862 title <<
"# Partitions: " << m_curr_partitions.size();
1863 this->m_win_manager->addTextMessage(
1864 5, -m_lc_params.offset_y_map_partitions, title.str(),
1866 m_lc_params.text_index_map_partitions);
1882 int partitionID = 0;
1883 bool partition_contains_last_node =
false;
1884 bool found_last_node =
1887 "Searching for the partition of the last nodeID: " 1888 << (this->m_graph->nodeCount() - 1));
1891 p_it != m_curr_partitions.end(); ++p_it, ++partitionID)
1898 nodes_list.begin(), nodes_list.end(),
1899 this->m_graph->nodeCount() - 1) != nodes_list.end())
1901 partition_contains_last_node =
true;
1903 found_last_node =
true;
1907 partition_contains_last_node =
false;
1916 map_partitions_obj->getByName(partition_obj_name);
1924 if (m_lc_params.LC_check_curr_partition_only)
1926 curr_partition_obj->
setVisibility(partition_contains_last_node);
1932 "\tCreating a new CSetOfObjects partition object for partition " 1935 curr_partition_obj = mrpt::make_aligned_shared<CSetOfObjects>();
1936 curr_partition_obj->setName(partition_obj_name);
1937 if (m_lc_params.LC_check_curr_partition_only)
1940 curr_partition_obj->setVisibility(partition_contains_last_node);
1945 CSphere::Ptr balloon_obj = mrpt::make_aligned_shared<CSphere>();
1946 balloon_obj->setName(balloon_obj_name);
1947 balloon_obj->setRadius(m_lc_params.balloon_radius);
1948 balloon_obj->setColor_u8(m_lc_params.balloon_std_color);
1949 balloon_obj->enableShowName();
1951 curr_partition_obj->insert(balloon_obj);
1957 mrpt::make_aligned_shared<CSetOfLines>();
1958 connecting_lines_obj->setName(
"connecting_lines");
1959 connecting_lines_obj->setColor_u8(
1960 m_lc_params.connecting_lines_color);
1961 connecting_lines_obj->setLineWidth(0.1f);
1963 curr_partition_obj->insert(connecting_lines_obj);
1968 map_partitions_obj->insert(curr_partition_obj);
1975 std::pair<double, double> centroid_coords;
1976 this->computeCentroidOfNodesVector(nodes_list, ¢roid_coords);
1979 centroid_coords.first, centroid_coords.second,
1980 m_lc_params.balloon_elevation);
1989 curr_partition_obj->getByName(balloon_obj_name);
1990 balloon_obj = std::dynamic_pointer_cast<
CSphere>(
obj);
1992 if (partition_contains_last_node)
1993 balloon_obj->
setColor_u8(m_lc_params.balloon_curr_color);
1995 balloon_obj->
setColor_u8(m_lc_params.balloon_std_color);
2008 curr_partition_obj->getByName(
"connecting_lines");
2009 connecting_lines_obj = std::dynamic_pointer_cast<
CSetOfLines>(
obj);
2011 connecting_lines_obj->
clear();
2014 it != nodes_list.end(); ++it)
2016 CPose3D curr_pose(this->m_graph->nodes.at(*it));
2017 TPoint3D curr_node_location(curr_pose);
2020 curr_node_location, balloon_location);
2021 connecting_lines_obj->appendLine(connecting_line);
2027 if (!found_last_node)
2030 "Last inserted nodeID was not found in any partition.");
2039 size_t prev_size = m_last_partitions.size();
2040 size_t curr_size = m_curr_partitions.size();
2041 if (curr_size < prev_size)
2044 for (
size_t partitionID = curr_size; partitionID != prev_size;
2049 "partition_%lu", static_cast<unsigned long>(partitionID));
2052 map_partitions_obj->getByName(partition_obj_name);
2056 "Partition : " << partition_obj_name <<
" was not found.");
2059 map_partitions_obj->removeObject(
obj);
2064 this->m_win->unlockAccess3DScene();
2065 this->m_win->forceRepaint();
2068 template <
class GRAPH_T>
2072 ASSERTMSG_(this->m_win,
"No CDisplayWindow3D* was provided");
2073 ASSERTMSG_(this->m_win_manager,
"No CWindowManager* was provided");
2077 this->logFmt(LVL_INFO,
"Toggling map partitions visualization...");
2080 if (m_lc_params.visualize_map_partitions)
2083 scene->getByName(
"map_partitions");
2084 obj->setVisibility(!
obj->isVisible());
2088 this->dumpVisibilityErrorMsg(
"visualize_map_partitions");
2091 this->m_win->unlockAccess3DScene();
2092 this->m_win->forceRepaint();
2097 template <
class GRAPH_T>
2100 std::pair<double, double>* centroid_coords)
const 2106 double centroid_x = 0;
2107 double centroid_y = 0;
2109 node_it != nodes_list.end(); ++node_it)
2111 pose_t curr_node_pos = this->m_graph->nodes.at(*node_it);
2112 centroid_x += curr_node_pos.x();
2113 centroid_y += curr_node_pos.y();
2117 centroid_coords->first =
2118 centroid_x /
static_cast<double>(nodes_list.size());
2119 centroid_coords->second =
2120 centroid_y /
static_cast<double>(nodes_list.size());
2125 template <
class GRAPH_T>
2131 if (m_laser_params.visualize_laser_scans)
2134 this->m_win->get3DSceneAndLock();
2137 mrpt::make_aligned_shared<mrpt::opengl::CPlanarLaserScan>();
2138 laser_scan_viz->enablePoints(
true);
2139 laser_scan_viz->enableLine(
true);
2140 laser_scan_viz->enableSurface(
true);
2141 laser_scan_viz->setSurfaceColor(
2142 m_laser_params.laser_scans_color.R,
2143 m_laser_params.laser_scans_color.G,
2144 m_laser_params.laser_scans_color.B,
2145 m_laser_params.laser_scans_color.A);
2147 laser_scan_viz->setName(
"laser_scan_viz");
2149 scene->insert(laser_scan_viz);
2150 this->m_win->unlockAccess3DScene();
2151 this->m_win->forceRepaint();
2157 template <
class GRAPH_T>
2163 if (m_laser_params.visualize_laser_scans && m_last_laser_scan2D)
2166 this->m_win->get3DSceneAndLock();
2169 scene->getByName(
"laser_scan_viz");
2173 laser_scan_viz->setScan(*m_last_laser_scan2D);
2177 this->m_graph->nodes.find(this->m_graph->nodeCount() - 1);
2178 if (search != this->m_graph->nodes.end())
2180 laser_scan_viz->setPose(search->second);
2183 laser_scan_viz->setPose(
2185 laser_scan_viz->getPoseX(), laser_scan_viz->getPoseY(),
2191 this->m_win->unlockAccess3DScene();
2192 this->m_win->forceRepaint();
2198 template <
class GRAPH_T>
2202 ASSERTMSG_(this->m_win,
"No CDisplayWindow3D* was provided");
2203 ASSERTMSG_(this->m_win_manager,
"No CWindowManager* was provided");
2206 this->logFmt(LVL_INFO,
"Toggling LaserScans visualization...");
2210 if (m_laser_params.visualize_laser_scans)
2213 scene->getByName(
"laser_scan_viz");
2214 obj->setVisibility(!
obj->isVisible());
2218 this->dumpVisibilityErrorMsg(
"visualize_laser_scans");
2221 this->m_win->unlockAccess3DScene();
2222 this->m_win->forceRepaint();
2227 template <
class GRAPH_T>
2229 std::map<std::string, int>* edge_types_to_num)
const 2232 *edge_types_to_num = m_edge_types_to_nums;
2236 template <
class GRAPH_T>
2240 parent_t::initializeVisuals();
2242 this->m_time_logger.enter(
"Visuals");
2245 m_laser_params.has_read_config,
2246 "Configuration parameters aren't loaded yet");
2247 if (m_laser_params.visualize_laser_scans)
2249 this->initLaserScansVisualization();
2251 if (m_lc_params.visualize_map_partitions)
2253 this->initMapPartitionsVisualization();
2256 if (m_visualize_curr_node_covariance)
2258 this->initCurrCovarianceVisualization();
2261 this->m_time_logger.leave(
"Visuals");
2264 template <
class GRAPH_T>
2268 parent_t::updateVisuals();
2270 this->m_time_logger.enter(
"Visuals");
2272 if (m_laser_params.visualize_laser_scans)
2274 this->updateLaserScansVisualization();
2276 if (m_lc_params.visualize_map_partitions)
2278 this->updateMapPartitionsVisualization();
2280 if (m_visualize_curr_node_covariance)
2282 this->updateCurrCovarianceVisualization();
2285 this->m_time_logger.leave(
"Visuals");
2289 template <
class GRAPH_T>
2293 using namespace std;
2297 this->m_win_manager->assignTextMessageParameters(
2298 &m_offset_y_curr_node_covariance,
2299 &m_text_index_curr_node_covariance);
2302 this->m_win_manager->addTextMessage(
2303 5, -m_offset_y_curr_node_covariance, title,
2305 m_text_index_curr_node_covariance);
2308 CEllipsoid::Ptr cov_ellipsis_obj = mrpt::make_aligned_shared<CEllipsoid>();
2309 cov_ellipsis_obj->setName(
"cov_ellipsis_obj");
2310 cov_ellipsis_obj->setColor_u8(m_curr_node_covariance_color);
2311 cov_ellipsis_obj->setLocation(0, 0, 0);
2315 scene->insert(cov_ellipsis_obj);
2316 this->m_win->unlockAccess3DScene();
2317 this->m_win->forceRepaint();
2322 template <
class GRAPH_T>
2326 using namespace std;
2334 path_t* path = queryOptimalPath(curr_node);
2340 pose_t curr_position = this->m_graph->nodes.at(curr_node);
2342 stringstream ss_mat;
2346 "In updateCurrCovarianceVisualization\n" 2347 "Covariance matrix:\n%s\n" 2349 ss_mat.str().c_str(), mat.det());
2357 cov_ellipsis_obj->
setLocation(curr_position.x(), curr_position.y(), 0);
2360 cov_ellipsis_obj->setCovMatrix(mat, 2);
2362 this->m_win->unlockAccess3DScene();
2363 this->m_win->forceRepaint();
2368 template <
class GRAPH_T>
2375 mrpt::utils::LVL_ERROR,
2376 "Cannot toggle visibility of specified object.\n " 2377 "Make sure that the corresponding visualization flag ( %s " 2378 ") is set to true in the .ini file.\n",
2380 std::this_thread::sleep_for(std::chrono::milliseconds(sleep_time));
2385 template <
class GRAPH_T>
2389 parent_t::loadParams(source_fname);
2391 m_partitioner.options.loadFromConfigFileName(
2392 source_fname,
"EdgeRegistrationDeciderParameters");
2393 m_laser_params.loadFromConfigFileName(
2394 source_fname,
"EdgeRegistrationDeciderParameters");
2395 m_lc_params.loadFromConfigFileName(
2396 source_fname,
"EdgeRegistrationDeciderParameters");
2400 m_consec_icp_constraint_factor =
source.read_double(
2401 "EdgeRegistrationDeciderParameters",
"consec_icp_constraint_factor",
2403 m_lc_icp_constraint_factor =
source.read_double(
2404 "EdgeRegistrationDeciderParameters",
"lc_icp_constraint_factor", 0.70,
2408 int min_verbosity_level =
source.read_int(
2409 "EdgeRegistrationDeciderParameters",
"class_verbosity", 1,
false);
2411 this->setMinLoggingLevel(mrpt::utils::VerbosityLevel(min_verbosity_level));
2414 template <
class GRAPH_T>
2418 using namespace std;
2420 cout <<
"------------------[Pair-wise Consistency of ICP Edges - " 2421 "Registration Procedure Summary]------------------" 2424 parent_t::printParams();
2425 m_partitioner.options.dumpToConsole();
2426 m_laser_params.dumpToConsole();
2427 m_lc_params.dumpToConsole();
2429 cout <<
"Scan-matching ICP Constraint factor: " 2430 << m_consec_icp_constraint_factor << endl;
2431 cout <<
"Loop-closure ICP Constraint factor: " 2432 << m_lc_icp_constraint_factor << endl;
2438 template <
class GRAPH_T>
2445 std::stringstream class_props_ss;
2446 class_props_ss <<
"Pair-wise Consistency of ICP Edges - Registration " 2447 "Procedure Summary: " 2449 class_props_ss << this->header_sep << std::endl;
2452 const std::string time_res = this->m_time_logger.getStatsAsText();
2453 const std::string output_res = this->getLogAsString();
2456 report_str->clear();
2457 parent_t::getDescriptiveReport(report_str);
2459 *report_str += class_props_ss.str();
2460 *report_str += this->report_sep;
2462 *report_str += time_res;
2463 *report_str += this->report_sep;
2465 *report_str += output_res;
2466 *report_str += this->report_sep;
2471 template <
class GRAPH_T>
2476 *partitions_out = this->getCurrPartitions();
2479 template <
class GRAPH_T>
2480 const std::vector<mrpt::vector_uint>&
2483 return m_curr_partitions;
2486 template <
class GRAPH_T>
2488 bool full_update ,
bool is_first_time_node_reg )
2493 using namespace std;
2495 this->m_time_logger.enter(
"updateMapPartitions");
2503 "updateMapPartitions: Full partitioning of map was issued");
2507 m_partitioner.clear();
2508 nodes_to_scans = this->m_nodes_to_laser_scans2D;
2513 if (is_first_time_node_reg)
2515 nodes_to_scans.insert(
2517 this->m_graph->root,
2518 this->m_nodes_to_laser_scans2D.at(this->m_graph->root)));
2522 nodes_to_scans.insert(
2524 this->m_graph->nodeCount() - 1,
2525 this->m_nodes_to_laser_scans2D.at(
2526 this->m_graph->nodeCount() - 1)));
2533 nodes_to_scans.begin();
2534 it != nodes_to_scans.end(); ++it)
2539 "nodeID \"" << it->first <<
"\" has invalid laserScan");
2546 search = this->m_graph->nodes.find(it->first);
2547 if (search == this->m_graph->nodes.end())
2554 pose_t curr_pose = search->second;
2559 mrpt::make_aligned_shared<mrpt::obs::CSensoryFrame>();
2560 sf->insert(it->second);
2562 m_partitioner.addMapFrame(sf, posePDF);
2567 size_t curr_size = m_curr_partitions.size();
2568 m_last_partitions.resize(curr_size);
2569 for (
size_t i = 0; i < curr_size; i++)
2571 m_last_partitions[i] = m_curr_partitions[i];
2574 m_partitioner.updatePartitions(m_curr_partitions);
2577 this->m_time_logger.leave(
"updateMapPartitions");
2584 template <
class GRAPH_T>
2586 : laser_scans_color(0, 20, 255),
2587 keystroke_laser_scans(
"l"),
2588 has_read_config(false)
2595 template <
class GRAPH_T>
2600 template <
class GRAPH_T>
2607 "Use scan-matching constraints = %s\n",
2608 use_scan_matching ?
"TRUE" :
"FALSE");
2610 "Num. of previous nodes to check ICP against = %d\n",
2611 prev_nodes_for_ICP);
2613 "Visualize laser scans = %s\n",
2614 visualize_laser_scans ?
"TRUE" :
"FALSE");
2618 template <
class GRAPH_T>
2625 source.read_bool(section,
"use_scan_matching",
true,
false);
2626 prev_nodes_for_ICP =
source.read_int(
2628 "prev_nodes_for_ICP",
2630 visualize_laser_scans =
source.read_bool(
2631 "VisualizationParameters",
"visualize_laser_scans",
true,
false);
2633 has_read_config =
true;
2639 template <
class GRAPH_T>
2641 : keystroke_map_partitions(
"b"),
2642 balloon_elevation(3),
2643 balloon_radius(0.5),
2644 balloon_std_color(153, 0, 153),
2645 balloon_curr_color(62, 0, 80),
2646 connecting_lines_color(balloon_std_color),
2647 has_read_config(false)
2651 template <
class GRAPH_T>
2656 template <
class GRAPH_T>
2661 using namespace std;
2664 ss <<
"Min. node difference for loop closure = " 2665 << LC_min_nodeid_diff << endl;
2666 ss <<
"Remote NodeIDs to consider the potential loop closure = " 2667 << LC_min_remote_nodes << endl;
2668 ss <<
"Min EigenValues ratio for accepting a hypotheses set = " 2669 << LC_eigenvalues_ratio_thresh << endl;
2670 ss <<
"Check only current node's partition for loop closures = " 2671 << (LC_check_curr_partition_only ?
"TRUE" :
"FALSE") << endl;
2672 ss <<
"New registered nodes required for full partitioning = " 2673 << full_partition_per_nodes << endl;
2674 ss <<
"Visualize map partitions = " 2675 << (visualize_map_partitions ?
"TRUE" :
"FALSE") << endl;
2677 out.
printf(
"%s", ss.str().c_str());
2681 template <
class GRAPH_T>
2687 LC_min_nodeid_diff =
source.read_int(
2688 "GeneralConfiguration",
"LC_min_nodeid_diff", 30,
false);
2689 LC_min_remote_nodes =
2690 source.read_int(section,
"LC_min_remote_nodes", 3,
false);
2691 LC_eigenvalues_ratio_thresh =
2692 source.read_double(section,
"LC_eigenvalues_ratio_thresh", 2,
false);
2693 LC_check_curr_partition_only =
2694 source.read_bool(section,
"LC_check_curr_partition_only",
true,
false);
2695 full_partition_per_nodes =
2696 source.read_int(section,
"full_partition_per_nodes", 50,
false);
2697 visualize_map_partitions =
source.read_bool(
2698 "VisualizationParameters",
"visualize_map_partitions",
true,
false);
2700 has_read_config =
true;
mrpt::obs::CObservation2DRangeScan::Ptr scan
void toggleMapPartitionsVisualization()
Toggle the map partitions visualization objects.
std::vector< mrpt::utils::TNodeID > nodes_traversed
Nodes that the Path comprises of.
bool mahalanobisDistanceOdometryToICPEdge(const mrpt::utils::TNodeID &from, const mrpt::utils::TNodeID &to, const constraint_t &rel_edge)
brief Compare the suggested ICP edge against the initial node difference.
GRAPH_T::global_pose_t pose
double goodness
Goodness value corresponding to the hypothesis edge.
parent_t::nodes_to_scans2D_t nodes_to_scans2D_t
Holds the data of an information path.
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
void loadParams(const std::string &source_fname)
bool getPropsOfNodeID(const mrpt::utils::TNodeID &nodeID, global_pose_t *pose, mrpt::obs::CObservation2DRangeScan::Ptr &scan, const node_props_t *node_props=NULL) const
Fill the pose and LaserScan for the given nodeID.
void addToPath(const mrpt::utils::TNodeID &node, const constraint_t &edge)
add a new link in the current path.
static const path_t * findPathByEnds(const paths_t &vec_paths, const mrpt::utils::TNodeID &src, const mrpt::utils::TNodeID &dst, bool throw_exc=true)
Given a vector of TUncertaintyPath objects, find the one that has the given source and destination no...
std::vector< uint32_t > vector_uint
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
double DEG2RAD(const double x)
Degrees to radians.
A set of object, which are referenced to the coordinates framework established in this object...
void initMapPartitionsVisualization()
Initialize the visualization of the map partition objects.
void computeCentroidOfNodesVector(const vector_uint &nodes_list, std::pair< double, double > *centroid_coords) const
Compute the Centroid of a group of a vector of node positions.
void getEdge(constraint_t *edge) const
Getter methods for the underlying edge.
void resizeWindow(size_t new_size)
Resize the window.
void updateCurrCovarianceVisualization()
This class allows loading and storing values and vectors of different types from ".ini" files easily.
#define THROW_EXCEPTION(msg)
virtual bool updateState(mrpt::obs::CActionCollection::Ptr action, mrpt::obs::CSensoryFrame::Ptr observations, mrpt::obs::CObservation::Ptr observation)
void getDescriptiveReport(std::string *report_str) const
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
CRenderizable & setLocation(double x, double y, double z)
Changes the location of the object, keeping untouched the orientation.
std::string getSTLContainerAsString(const T &t)
Return a STL container in std::string form.
std::shared_ptr< CRenderizable > Ptr
const Scalar * const_iterator
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string §ion)
This method load the options from a ".ini"-like file or memory-stored string list.
pose_t init_estim
Initial ICP estimation.
const_iterator find(const KEY &key) const
TSlidingWindow mahal_distance_ICP_odom_win
Keep track of the mahalanobis distance between the initial pose difference and the suggested new edge...
std::shared_ptr< CObservation2DRangeScan > Ptr
CMatrixFixedNumeric< double, 3, 3 > CMatrixDouble33
static hypot_t * findHypotByID(const hypotsp_t &vec_hypots, const size_t &id, bool throw_exc=true)
Given a vector of THypothesis objects, find the one that has the given ID.
GRAPH_T::edges_map_t::const_iterator edges_citerator
virtual bool getICPEdge(const mrpt::utils::TNodeID &from, const mrpt::utils::TNodeID &to, constraint_t *rel_edge, mrpt::slam::CICP::TReturnInfo *icp_info=NULL, const TGetICPEdgeAdParams *ad_params=NULL)
Get the ICP Edge between the provided nodes.
virtual ~CLoopCloserERD()
GLsizei GLsizei GLuint * obj
node_props_t from_params
Ad.
Struct for passing additional parameters to the getICPEdge call.
void addToPaths(std::set< path_t *> *pool_of_paths, const path_t &curr_path, const std::set< mrpt::utils::TNodeID > &neibors) const
Append the paths starting from the current node.
void registerHypothesis(const hypot_t &h)
Wrapper around the registerNewEdge method which accepts a THypothesis object instead.
void getAsString(std::string *str) const
GLubyte GLubyte GLubyte GLubyte w
void evaluatePartitionsForLC(const partitions_t &partitions)
Evaluate the given partitions for loop closures.
mrpt::utils::TNodeID from
Starting node of the hypothesis.
This class allows loading and storing values and vectors of different types from a configuration text...
bool is_valid
Field that specifies if the hypothesis is to be considered.
float goodness
A goodness measure for the alignment, it is a [0,1] range indicator of percentage of correspondences...
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
SLAM methods related to graphs of pose constraints.
This base provides a set of functions for maths stuff.
std::shared_ptr< CPosePDF > Ptr
3D segment, consisting of two points.
uint64_t TNodeID
The type for node IDs in graphs of different types.
constraint_t curr_pose_pdf
Current path position + corresponding covariance.
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
virtual void addScanMatchingEdges(const mrpt::utils::TNodeID &curr_nodeID)
Addd ICP constraints from X previous nodeIDs up to the given nodeID.
virtual void fetchNodeIDsForScanMatching(const mrpt::utils::TNodeID &curr_nodeID, std::set< mrpt::utils::TNodeID > *nodes_set)
Fetch a list of nodes with regards prior to the given nodeID for which to try and add scan matching e...
std::shared_ptr< CPlanarLaserScan > Ptr
Eigen::Matrix< dataType, 4, 4 > inverse(Eigen::Matrix< dataType, 4, 4 > &pose)
std::shared_ptr< CSetOfObjects > Ptr
This namespace contains representation of robot actions and observations.
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
This object renders a 2D laser scan by means of three elements: the points, the line along end-points...
const partitions_t & getCurrPartitions() const
std::shared_ptr< CSensoryFrame > Ptr
#define MRPT_LOG_WARN_STREAM(__CONTENTS)
uint64_t TNodeID
The type for node IDs in graphs of different types.
std::map< std::string, int > m_edge_types_to_nums
Keep track of the registered edge types.
void clear()
Clear the list of segments.
std::shared_ptr< CObservation > Ptr
std::vector< path_t > paths_t
GLsizei const GLchar ** string
bool computeDominantEigenVector(const mrpt::math::CMatrixDouble &consist_matrix, mrpt::math::dynamic_vector< double > *eigvec, bool use_power_method=false)
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 setWindowManagerPtr(mrpt::graphslam::CWindowManager *win_manager)
void dumpToTextStream(mrpt::utils::CStream &out) const
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
GRAPH_T::global_pose_t global_pose_t
void assertIsBetweenNodeIDs(const mrpt::utils::TNodeID &from, const mrpt::utils::TNodeID &to) const
Assert that the current path is between the given nodeIDs.
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.
void getInverseEdge(constraint_t *edge) const
Getter methods for the inverse of the underlying edge.
double generatePWConsistencyElement(const mrpt::utils::TNodeID &a1, const mrpt::utils::TNodeID &a2, const mrpt::utils::TNodeID &b1, const mrpt::utils::TNodeID &b2, const hypotsp_t &hypots, const paths_t *opt_paths=NULL)
Return the pair-wise consistency between the observations of the given nodes.
std::vector< mrpt::vector_uint > partitions_t
Typedef for referring to a list of partitions.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
std::shared_ptr< CActionCollection > Ptr
std::vector< hypot_t * > hypotsp_t
void setVisibility(bool visible=true)
Set object visibility (default=true)
void registerNewEdge(const mrpt::utils::TNodeID &from, const mrpt::utils::TNodeID &to, const constraint_t &rel_edge)
void dumpToTextStream(mrpt::utils::CStream &out) const
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
void splitPartitionToGroups(vector_uint &partition, vector_uint *groupA, vector_uint *groupB, int max_nodes_in_group=5)
Split an existing partition to Groups.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
virtual CRenderizable & setColor_u8(const mrpt::utils::TColor &c)
mrpt::utils::TNodeID to
Ending node of the hypothesis.
node_props_t to_params
Ad.
void updateLaserScansVisualization()
A solid or wire-frame sphere.
void checkPartitionsForLC(partitions_t *partitions_for_LC)
Check the registered so far partitions for potential loop closures.
std::shared_ptr< COpenGLScene > Ptr
Struct for passing additional parameters to the generateHypotsPool call.
The ICP algorithm return information.
void setEdge(const constraint_t &edge)
Setter method for the underlying edge.
void generatePWConsistenciesMatrix(const vector_uint &groupA, const vector_uint &groupB, const hypotsp_t &hypots_pool, mrpt::math::CMatrixDouble *consist_matrix, const paths_t *groupA_opt_paths=NULL, const paths_t *groupB_opt_paths=NULL)
Compute the pair-wise consistencies Matrix.
static hypot_t * findHypotByEnds(const hypotsp_t &vec_hypots, const mrpt::utils::TNodeID &from, const mrpt::utils::TNodeID &to, bool throw_exc=true)
Given a vector of THypothesis objects, find the one that has the given start and end nodes...
The namespace for 3D scene representation and rendering.
GLsizei GLsizei GLchar * source
A RGB color - floats in the range [0,1].
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.
GRAPH_T::constraint_t::type_value pose_t
type of underlying poses (2D/3D).
std::shared_ptr< CSetOfLines > Ptr
Edge Registration Decider scheme specialized in Loop Closing.
void getMinUncertaintyPath(const mrpt::utils::TNodeID from, const mrpt::utils::TNodeID to, path_t *path) const
Given two nodeIDs compute and return the path connecting them.
std::map< mrpt::utils::TNodeID, node_props_t > group_t
void generateHypotsPool(const vector_uint &groupA, const vector_uint &groupB, hypotsp_t *generated_hypots, const TGenerateHypotsPoolAdParams *ad_params=NULL)
Generate the hypothesis pool for all the inter-group constraints between two groups of nodes...
Classes for creating GUI windows for 2D and 3D visualization.
T absDiff(const T &lhs, const T &rhs)
Absolute difference between two numbers.
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.
GLsizei const GLfloat * value
void initCurrCovarianceVisualization()
void execDijkstraProjection(mrpt::utils::TNodeID starting_node=0, mrpt::utils::TNodeID ending_node=INVALID_NODEID)
compute the minimum uncertainty of each node position with regards to the graph root.
void updateMapPartitionsVisualization()
Update the map partitions visualization.
void initLaserScansVisualization()
A 2D ellipse or 3D ellipsoid, depending on the size of the m_cov matrix (2x2 or 3x3).
size_t id
ID of the current hypothesis.
void notifyOfWindowEvents(const std::map< std::string, bool > &events_occurred)
An edge hypothesis between two 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 MRPT_LOG_DEBUG_STREAM(__CONTENTS)
#define ASSERTMSG_(f, __ERROR_MSG)
#define MRPT_LOG_ERROR_STREAM(__CONTENTS)
std::shared_ptr< CSphere > Ptr
GLenum const GLfloat * params
void getEdgesStats(std::map< std::string, int > *edge_types_to_num) const
Internal auxiliary classes.
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string §ion)
This method load the options from a ".ini"-like file or memory-stored string list.
bool fillNodePropsFromGroupParams(const mrpt::utils::TNodeID &nodeID, const std::map< mrpt::utils::TNodeID, node_props_t > &group_params, node_props_t *node_props)
Fill the TNodeProps instance using the parameters from the map.
const mrpt::utils::TNodeID & getDestination() const
Return the Destination node of this path.
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 int printf(const char *fmt,...) MRPT_printf_format_check(2
Writes a string to the stream in a textual form.
GRAPH_T::constraint_t constraint_t
Handy typedefs.
std::string getAsString(bool oneline=true) const
Return a string representation of the object at hand.
std::shared_ptr< CEllipsoid > Ptr
TSlidingWindow goodness_threshold_win
Keep track of ICP Goodness values for ICP between nearby nodes and adapt the Goodness threshold based...