CGraphSlamEngine_MR_impl.h
Go to the documentation of this file.
00001 /* +---------------------------------------------------------------------------+
00002          |                     Mobile Robot Programming Toolkit (MRPT)               |
00003          |                          http://www.mrpt.org/                             |
00004          |                                                                           |
00005          | Copyright (c) 2005-2016, Individual contributors, see AUTHORS file        |
00006          | See: http://www.mrpt.org/Authors - All rights reserved.                   |
00007          | Released under BSD License. See details in http://www.mrpt.org/License    |
00008          +---------------------------------------------------------------------------+ */
00009 
00010 #pragma once
00011 
00012 #include <thread>
00013 #include <chrono>
00014 #include <mrpt/version.h>
00015 
00016 #if MRPT_VERSION>=0x199
00017 #include <mrpt/math/CMatrixFixed.h>
00018 namespace mrpt::math{
00019 // backwards compatible
00020 template <typename T, std::size_t ROWS, std::size_t COLS>
00021 using CMatrixFixedNumeric = CMatrixFixed<T,ROWS,COLS>;
00022 }
00023 #endif
00024 
00025 
00026 namespace mrpt { namespace graphslam {
00027 
00028 template<class GRAPH_T>
00029 CGraphSlamEngine_MR<GRAPH_T>::CGraphSlamEngine_MR(
00030                 ros::NodeHandle* nh,
00031                 const std::string& config_file,
00032                 const std::string& rawlog_fname/* ="" */,
00033                 const std::string& fname_GT /* ="" */,
00034                 mrpt::graphslam::CWindowManager* win_manager /* = NULL */,
00035                 mrpt::graphslam::deciders::CNodeRegistrationDecider<GRAPH_T>* node_reg /* = NULL */,
00036                 mrpt::graphslam::deciders::CEdgeRegistrationDecider<GRAPH_T>* edge_reg /* = NULL */,
00037                 mrpt::graphslam::optimizers::CGraphSlamOptimizer<GRAPH_T>* optimizer /* = NULL */):
00038         parent_t::CGraphSlamEngine_ROS(
00039                         nh,
00040                         config_file,
00041                         rawlog_fname,
00042                         fname_GT,
00043                         win_manager,
00044                         node_reg,
00045                         edge_reg,
00046                         optimizer),
00047         m_conn_manager(
00048                         dynamic_cast<mrpt::utils::COutputLogger*>(this), nh),
00049         m_nh(nh),
00050         m_graph_nodes_last_size(0),
00051         m_registered_multiple_nodes(false),
00052         cm_graph_async_spinner(/* threads_num: */ 1, &this->custom_service_queue),
00053         m_sec_alignment_params("AlignmentParameters"),
00054         m_sec_mr_slam_params("MultiRobotParameters"),
00055         m_opts(*this)
00056 {
00057         this->initClass();
00058 }
00059 
00060 template<class GRAPH_T>
00061 CGraphSlamEngine_MR<GRAPH_T>::~CGraphSlamEngine_MR() {
00062         MRPT_LOG_DEBUG_STREAM(
00063                 "In Destructor: Deleting CGraphSlamEngine_MR instance...");
00064         cm_graph_async_spinner.stop();
00065 
00066         for (typename neighbors_t::iterator
00067                         neighbors_it = m_neighbors.begin();
00068                         neighbors_it != m_neighbors.end();
00069                         ++neighbors_it) {
00070                 delete *neighbors_it;
00071         }
00072 
00073 }
00074 
00075 template<class GRAPH_T>
00076 bool CGraphSlamEngine_MR<GRAPH_T>::addNodeBatchesFromAllNeighbors() {
00077         MRPT_START;
00078         using namespace mrpt::graphslam::detail;
00079 
00080         bool ret_val = false;
00081         for (const auto& neighbor : m_neighbors) {
00082                 if (!isEssentiallyZero(
00083                                         neighbor->tf_self_to_neighbor_first_integrated_pose) && // inter-graph TF found
00084                                 neighbor->hasNewData() &&
00085                                 neighbor->hasNewNodesBatch(m_opts.nodes_integration_batch_size)) {
00086                         bool loc_ret_val = this->addNodeBatchFromNeighbor(neighbor);
00087                         if (loc_ret_val) { ret_val = true; }
00088                 }
00089         }
00090 
00091         return ret_val;
00092         MRPT_END;
00093 } // end of addNodeBatchesFromAllNeighbors
00094 
00095 template<class GRAPH_T>
00096 bool CGraphSlamEngine_MR<GRAPH_T>::
00097 addNodeBatchFromNeighbor(TNeighborAgentProps* neighbor) {
00098         MRPT_START;
00099         ASSERT_(neighbor);
00100         using namespace mrpt::utils;
00101         using namespace mrpt::poses;
00102         using namespace mrpt::math;
00103         using namespace std;
00104 
00105 
00106         std::vector<TNodeID> nodeIDs;
00107         std::map<TNodeID, node_props_t> nodes_params;
00108         neighbor->getCachedNodes(&nodeIDs, &nodes_params, /*only unused=*/ true);
00109 
00110         //
00111         // get the condensed measurements graph of the new nodeIDs
00112         //
00113         mrpt_msgs::GetCMGraph cm_graph_srv;
00114         //mrpt_msgs::GetCMGraphRequest::_nodeIDs_type& cm_graph_nodes =
00115         //cm_graph_srv.request.nodeIDs;
00116         for (const auto n : nodeIDs) {
00117                 cm_graph_srv.request.nodeIDs.push_back(n);
00118         }
00119 
00120         MRPT_LOG_DEBUG_STREAM("Asking for the graph.");
00121         bool res = neighbor->cm_graph_srvclient.call(cm_graph_srv); // blocking
00122         if (!res) {
00123                 MRPT_LOG_ERROR_STREAM("Service call for CM_Graph failed.");
00124                 return false; // skip this if failed to fetch other's graph
00125         }
00126         MRPT_LOG_DEBUG_STREAM("Fetched graph successfully.");
00127         MRPT_LOG_DEBUG_STREAM(cm_graph_srv.response.cm_graph);
00128 
00129         GRAPH_T other_graph;
00130         mrpt_bridge::convert(cm_graph_srv.response.cm_graph, other_graph);
00131 
00132         //
00133         // merge batch of nodes in own graph
00134         //
00135         MRPT_LOG_WARN_STREAM("Merging new batch from \"" << neighbor->getAgentNs() << "\"..." << endl
00136                 << "Batch: " << getSTLContainerAsString(cm_graph_srv.request.nodeIDs));
00137         hypots_t graph_conns;
00138         // build a hypothesis connecting the new batch with the last integrated
00139         // pose of the neighbor
00140         {
00141                 pair<TNodeID, node_props_t> node_props_to_connect = *nodes_params.begin();
00142 
00143                 hypot_t graph_conn;
00144                 constraint_t c;
00145                 c.mean = node_props_to_connect.second.pose -
00146                         neighbor->last_integrated_pair_neighbor_frame.second;
00147 #if MRPT_VERSION>=0x199
00148                 c.cov_inv.setIdentity();
00149 #else
00150                 c.cov_inv.unit();
00151 #endif
00152                 graph_conn.setEdge(c);
00153 
00154                 graph_conn.from = INVALID_NODEID;
00155                 // get the nodeID of the last integrated neighbor node after remapping
00156                 // in own graph numbering
00157                 for (const auto n : this->m_graph.nodes) {
00158                         if (n.second.agent_ID_str == neighbor->getAgentNs() &&
00159                                         n.second.nodeID_loc == neighbor->last_integrated_pair_neighbor_frame.first) {
00160                                 graph_conn.from = n.first;
00161                                 break;
00162                         }
00163                 }
00164                 ASSERT_(graph_conn.from != INVALID_NODEID);
00165                 graph_conn.to = node_props_to_connect.first; // other
00166 
00167                 MRPT_LOG_DEBUG_STREAM("Hypothesis for adding the batch of nodes: " << graph_conn);
00168                 graph_conns.push_back(graph_conn);
00169         }
00170 
00171         std::map<TNodeID, TNodeID> old_to_new_mappings;
00172         this->m_graph.mergeGraph(
00173                         other_graph, graph_conns,
00174                         /*hypots_from_other_to_self=*/ false,
00175                         &old_to_new_mappings);
00176 
00177         //
00178         // Mark Nodes/LaserScans as integrated
00179         //
00180         MRPT_LOG_WARN_STREAM("Marking used nodes as integrated - Integrating LSs");
00181         nodes_to_scans2D_t new_nodeIDs_to_scans_pairs;
00182         for (typename std::vector<TNodeID>::const_iterator
00183                         n_cit = nodeIDs.begin();
00184                         n_cit != nodeIDs.end();
00185                         ++n_cit) {
00186 
00187                 // Mark the neighbor's used nodes as integrated
00188                 neighbor->nodeID_to_is_integrated.at(*n_cit) = true;
00189 
00190                 // Integrate LaserScans at the newly integrated nodeIDs in own
00191                 // nodes_to_laser_scans2D map
00192                 new_nodeIDs_to_scans_pairs.insert(make_pair(
00193                                         old_to_new_mappings.at(*n_cit),
00194                                         nodes_params.at(*n_cit).scan));
00195                 MRPT_LOG_INFO_STREAM("Adding nodeID-LS of nodeID: "
00196                         << "\t[old:] " << *n_cit << endl
00197                         << "| [new:] " << old_to_new_mappings.at(*n_cit));
00198         }
00199 
00200         this->m_nodes_to_laser_scans2D.insert(
00201                         new_nodeIDs_to_scans_pairs.begin(),
00202                         new_nodeIDs_to_scans_pairs.end());
00203         edge_reg_mr_t* edge_reg_mr =
00204                 dynamic_cast<edge_reg_mr_t*>(this->m_edge_reg);
00205         edge_reg_mr->addBatchOfNodeIDsAndScans(new_nodeIDs_to_scans_pairs);
00206 
00207         this->execDijkstraNodesEstimation();
00208         neighbor->resetFlags();
00209 
00210         // keep track of the last integrated nodeID
00211         {
00212                 TNodeID last_node = *nodeIDs.rbegin();
00213                 neighbor->last_integrated_pair_neighbor_frame = make_pair(
00214                                 last_node,
00215                                 nodes_params.at(last_node).pose);
00216         }
00217 
00218         return true;
00219         MRPT_END;
00220 } // end of addNodeBatchFromNeighbor
00221 
00222 template<class GRAPH_T>
00223 bool CGraphSlamEngine_MR<GRAPH_T>::findTFsWithAllNeighbors() {
00224         MRPT_START;
00225         using namespace mrpt::utils;
00226         using namespace mrpt::math;
00227 
00228         if (this->m_graph.nodeCount() < m_opts.inter_group_node_count_thresh) {
00229                 return false;
00230         }
00231 
00232 
00233         // cache the gridmap so that it is computed only once during all the
00234         // findMatches*  calls
00235         this->computeMap();
00236 
00237         bool ret_val = false; // at *any* node registration, change to true
00238 
00239         // iterate over all neighbors - run map-matching proc.
00240         for (typename neighbors_t::iterator
00241                         neighbors_it = m_neighbors.begin();
00242                         neighbors_it != m_neighbors.end();
00243                         ++neighbors_it) {
00244 
00245                 // run matching proc with neighbor only if I haven't found an initial
00246                 // inter-graph TF
00247                 if (!m_neighbor_to_found_initial_tf.at(*neighbors_it)) {
00248 
00249                         bool loc_ret_val = findTFWithNeighbor(*neighbors_it);
00250                         if (loc_ret_val) {
00251                                 MRPT_LOG_DEBUG_STREAM(
00252                                         "Updating own cached map after successful node registration...");
00253                                 // update own map if new nodes have been added.
00254                                 this->computeMap();
00255 
00256                                 // mark current neighbor tf as found.
00257                                 m_neighbor_to_found_initial_tf.at(*neighbors_it) = true;
00258 
00259                                 ret_val = true;
00260                         }
00261                 }
00262         }
00263 
00264         return ret_val;
00265         MRPT_END;
00266 } // end of findTFsWithAllNeighbors
00267 
00268 template<class GRAPH_T>
00269 bool CGraphSlamEngine_MR<GRAPH_T>::
00270 findTFWithNeighbor(TNeighborAgentProps* neighbor) {
00271         MRPT_START;
00272         using namespace mrpt::slam;
00273         using namespace mrpt::math;
00274         using namespace mrpt::poses;
00275         using namespace mrpt::utils;
00276         using namespace mrpt::maps;
00277         using namespace mrpt::graphslam::detail;
00278 
00279         bool ret_val = false;
00280 
00281         std::vector<TNodeID> neighbor_nodes;
00282         std::map<TNodeID, node_props_t> nodes_params;
00283         neighbor->getCachedNodes(&neighbor_nodes, &nodes_params, /*only unused=*/ false);
00284         if (neighbor_nodes.size() < m_opts.inter_group_node_count_thresh ||
00285                         !neighbor->hasNewData()) {
00286                 return false;
00287         }
00288 
00289         //
00290         // run alignment procedure
00291         //
00292         COccupancyGridMap2D::Ptr neighbor_gridmap = neighbor->getGridMap();
00293         CGridMapAligner gridmap_aligner;
00294         gridmap_aligner.options = m_alignment_options;
00295 
00296         CGridMapAligner::TReturnInfo results;
00297         float run_time = 0;
00298         // TODO - make use of agents' rendez-vous in the initial estimation
00299         CPosePDFGaussian init_estim;
00300         init_estim.mean = neighbor->tf_self_to_neighbor_first_integrated_pose;
00301         this->logFmt(LVL_INFO,
00302                         "Trying to align the maps, initial estimation: %s",
00303                         init_estim.mean.asString().c_str());
00304 
00305         // Save them for debugging reasons
00306         //neighbor_gridmap->saveMetricMapRepresentationToFile(this->getLoggerName() + "_other");
00307         //this->m_gridmap_cached->saveMetricMapRepresentationToFile(this->getLoggerName() + "_self");
00308 
00309         const CPosePDF::Ptr pdf_tmp = gridmap_aligner.AlignPDF(
00310                         this->m_gridmap_cached.get(), neighbor_gridmap.get(),
00311                         init_estim,
00312                         &run_time, &results);
00313         this->logFmt(LVL_INFO, "Elapsed Time: %f", run_time);
00314         CPosePDFSOG::Ptr pdf_out = CPosePDFSOG::Create();
00315         pdf_out->copyFrom(*pdf_tmp);
00316 
00317         CPose2D pose_out; CMatrixDouble33 cov_out;
00318         pdf_out->getMostLikelyCovarianceAndMean(cov_out, pose_out);
00319 
00320         this->logFmt(LVL_INFO, "%s\n",
00321                         getGridMapAlignmentResultsAsString(*pdf_tmp, results).c_str());
00322 
00323         // dismiss this?
00324         if (results.goodness > 0.999 ||
00325                         isEssentiallyZero(pose_out)) {
00326                 return false;
00327         }
00328 
00329         //
00330         //
00331         // Map-merging operation is successful. Integrate graph into own.
00333 
00334         //
00335         // ask for condensed measurements graph
00336         //
00337         mrpt_msgs::GetCMGraph cm_graph_srv;
00338         typedef mrpt_msgs::GetCMGraphRequest::_nodeIDs_type nodeID_type;
00339         nodeID_type& matched_nodeIDs =
00340                 cm_graph_srv.request.nodeIDs;
00341 
00342         // which nodes to ask the condensed graph for
00343         // I assume that no nodes of the other graph have been integrated yet.
00344         for (typename std::vector<TNodeID>::const_iterator
00345                         n_cit = neighbor_nodes.begin();
00346                         n_cit != neighbor_nodes.end();
00347                         ++n_cit) {
00348                 matched_nodeIDs.push_back(*n_cit); // all used nodes
00349         }
00350 
00351         MRPT_LOG_DEBUG_STREAM("Asking for the graph.");
00352         bool res = neighbor->cm_graph_srvclient.call(cm_graph_srv); // blocking
00353         if (!res) {
00354                 MRPT_LOG_ERROR_STREAM("Service call for CM_Graph failed.");
00355                 return false; // skip this if failed to fetch other's graph
00356         }
00357         MRPT_LOG_DEBUG_STREAM("Fetched graph successfully.");
00358         MRPT_LOG_DEBUG_STREAM(cm_graph_srv.response.cm_graph);
00359 
00360         GRAPH_T other_graph;
00361         mrpt_bridge::convert(cm_graph_srv.response.cm_graph, other_graph);
00362 
00363         //
00364         // merge graphs
00365         //
00366         MRPT_LOG_WARN_STREAM("Merging graph of \"" << neighbor->getAgentNs() << "\"...");
00367         hypots_t graph_conns;
00368         // build the only hypothesis connecting graph with neighbor subgraph
00369         // own origin -> first valid nodeID of neighbor
00370         {
00371                 hypot_t graph_conn;
00372                 constraint_t c;
00373                 c.mean = pose_out;
00374                  // assign the inverse of the found covariance to c
00375 #if MRPT_VERSION>=0x199
00376                 cov_out = c.cov_inv.inverse();
00377 #else
00378                 cov_out.inv(c.cov_inv);
00379 #endif
00380                 graph_conn.setEdge(c);
00381                 // TODO - change this.
00382                 graph_conn.from = 0; // self
00383                 graph_conn.to = *neighbor_nodes.begin(); // other
00384 
00385                 graph_conn.goodness = results.goodness;
00386                 graph_conns.push_back(graph_conn);
00387         }
00388 
00389         std::map<TNodeID, TNodeID> old_to_new_mappings;
00390         this->m_graph.mergeGraph(
00391                         other_graph, graph_conns,
00392                         /*hypots_from_other_to_self=*/ false,
00393                         &old_to_new_mappings);
00394 
00395         //
00396         // Mark Nodes/LaserScans as integrated
00397         //
00398         MRPT_LOG_WARN_STREAM("Marking used nodes as integrated - Integrating LSs");
00399         nodes_to_scans2D_t new_nodeIDs_to_scans_pairs;
00400         for (typename std::vector<TNodeID>::const_iterator
00401                         n_cit = neighbor_nodes.begin();
00402                         n_cit != neighbor_nodes.end();
00403                         ++n_cit) {
00404 
00405                 // Mark the neighbor's used nodes as integrated
00406                 neighbor->nodeID_to_is_integrated.at(*n_cit) = true;
00407 
00408                 // Integrate LaserScans at the newly integrated nodeIDs in own
00409                 // nodes_to_laser_scans2D map
00410                 new_nodeIDs_to_scans_pairs.insert(make_pair(
00411                                         old_to_new_mappings.at(*n_cit),
00412                                         nodes_params.at(*n_cit).scan));
00413                 MRPT_LOG_INFO_STREAM("Adding nodeID-LS of nodeID: "
00414                         << "\t[old:] " << *n_cit << endl
00415                         << "| [new:] " << old_to_new_mappings.at(*n_cit));
00416         }
00417 
00418         this->m_nodes_to_laser_scans2D.insert(
00419                         new_nodeIDs_to_scans_pairs.begin(),
00420                         new_nodeIDs_to_scans_pairs.end());
00421         edge_reg_mr_t* edge_reg_mr =
00422                 dynamic_cast<edge_reg_mr_t*>(this->m_edge_reg);
00423         edge_reg_mr->addBatchOfNodeIDsAndScans(new_nodeIDs_to_scans_pairs);
00424 
00425         // Call for a Full graph visualization update and Dijkstra update -
00426         // CGraphSlamOptimizer
00427         //MRPT_LOG_WARN_STREAM("Optimizing graph..." << endl);
00428         //this->m_optimizer->optimizeGraph();
00429         MRPT_LOG_WARN_STREAM("Executing Dijkstra..." << endl);
00430         this->execDijkstraNodesEstimation();
00431 
00432         neighbor->resetFlags();
00433 
00434         // update the initial tf estimation
00435         neighbor->tf_self_to_neighbor_first_integrated_pose = pose_out;
00436 
00437         // keep track of the last integrated nodeID
00438         {
00439                 TNodeID last_node = *neighbor_nodes.rbegin();
00440                 neighbor->last_integrated_pair_neighbor_frame = make_pair(
00441                                 last_node,
00442                                 nodes_params.at(last_node).pose);
00443         }
00444 
00445         MRPT_LOG_WARN_STREAM("Nodes of neighbor [" << neighbor->getAgentNs()
00446                 << "] have been integrated successfully");
00447 
00448         ret_val = true;
00449 
00450         return ret_val;
00451         MRPT_END;
00452 } // end if findTFWithNeighbor
00453 
00454 template<class GRAPH_T>
00455 bool CGraphSlamEngine_MR<GRAPH_T>::_execGraphSlamStep(
00456                 mrpt::obs::CActionCollection::Ptr& action,
00457                 mrpt::obs::CSensoryFrame::Ptr& observations,
00458                 mrpt::obs::CObservation::Ptr& observation,
00459                 size_t& rawlog_entry) {
00460         MRPT_START;
00461         using namespace mrpt::graphslam::deciders;
00462         using namespace mrpt;
00463 
00464         // call parent method
00465         bool continue_exec = parent_t::_execGraphSlamStep(
00466                         action, observations, observation, rawlog_entry);
00467 
00468         // find matches between own nodes and those of the neighbors
00469   bool did_register_from_map_merge;
00470   if (!m_opts.conservative_find_initial_tfs_to_neighbors) {
00471         did_register_from_map_merge = this->findTFsWithAllNeighbors();
00472   }
00473   else { // inter-graph TF is available - add new nodes
00474         THROW_EXCEPTION("Conservative inter-graph TF computation is not yet implemented.");
00475   }
00476 
00477   bool did_register_from_batches = this->addNodeBatchesFromAllNeighbors();
00478   m_registered_multiple_nodes = (did_register_from_map_merge || did_register_from_batches);
00479 
00480   if (m_registered_multiple_nodes) {
00481         if (this->m_enable_visuals) {
00482                 this->updateAllVisuals();
00483         }
00484   }
00485 
00486   return continue_exec;
00487   MRPT_END;
00488 } // end of _execGraphSlamStep
00489 
00490 template<class GRAPH_T>
00491 void CGraphSlamEngine_MR<GRAPH_T>::initClass() {
00492         using namespace mrpt::graphslam;
00493         using namespace mrpt::utils;
00494         using namespace std;
00495 
00496         // initialization of topic namespace names
00497         // TODO - put these into seperate method
00498         m_mr_ns = "mr_info";
00499 
00500         // initialization of topic names / services
00501         m_list_neighbors_topic   = m_mr_ns + "/" + "neighbors";
00502         m_last_regd_id_scan_topic = m_mr_ns + "/" + "last_nodeID_laser_scan";
00503         m_last_regd_nodes_topic = m_mr_ns + "/" + "last_regd_nodes";
00504         m_cm_graph_service = m_mr_ns + "/" + "get_cm_graph";
00505 
00506         this->m_class_name = "CGraphSlamEngine_MR_" + m_conn_manager.getTrimmedNs();
00507         this->setLoggerName(this->m_class_name);
00508         this->setupComm();
00509 
00510         // Make sure that master_discovery and master_sync are up before trying to
00511         // connect to other agents
00512         std::vector<string> nodes_up;
00513         ros::master::getNodes(nodes_up);
00514         // If both master_dicovery and master_sync are running, then the
00515         // /master_sync/get_sync_info service should be available
00516         MRPT_LOG_INFO_STREAM("Waiting for master_discovery, master_sync nodes to come up....");
00517         ros::service::waitForService("/master_sync/get_sync_info"); // block until it is
00518         MRPT_LOG_INFO_STREAM("master_discovery, master_sync are available.");
00519 
00520         this->m_node_reg->setClassName(
00521                   this->m_node_reg->getClassName() + "_" + m_conn_manager.getTrimmedNs());
00522         this->m_edge_reg->setClassName(
00523                   this->m_edge_reg->getClassName() + "_" + m_conn_manager.getTrimmedNs());
00524         this->m_optimizer->setClassName(
00525                   this->m_optimizer->getClassName() + "_" + m_conn_manager.getTrimmedNs());
00526 
00527         // in case of Multi-robot specific deciders/optimizers (they
00528         // inherit from the CDeciderOrOptimizer_ROS interface) set the
00529         // CConnectionManager*
00530         // NOTE: It's not certain, even though we are running multi-robot graphSLAM
00531         // that all these classes do inherit from the
00532         // CRegistrationDeciderOrOptimizer_MR base class. They might be more generic
00533         // and not care about the multi-robot nature of the algorithm (e.g.
00534         // optimization scheme)
00535         { // NRD
00536                 CRegistrationDeciderOrOptimizer_MR<GRAPH_T>* dec_opt_mr =
00537                         dynamic_cast<CRegistrationDeciderOrOptimizer_MR<GRAPH_T>*>(this->m_node_reg);
00538 
00539                 if (dec_opt_mr) {
00540                         dec_opt_mr->setCConnectionManagerPtr(&m_conn_manager);
00541                 }
00542         }
00543         { // ERD
00544                 CRegistrationDeciderOrOptimizer_MR<GRAPH_T>* dec_opt_mr =
00545                         dynamic_cast<CRegistrationDeciderOrOptimizer_MR<GRAPH_T>*>(this->m_edge_reg);
00546                 ASSERT_(dec_opt_mr);
00547                 dec_opt_mr->setCConnectionManagerPtr(&m_conn_manager);
00548                 dec_opt_mr->setCGraphSlamEnginePtr(this);
00549         }
00550         { // GSO
00551                 CRegistrationDeciderOrOptimizer_MR<GRAPH_T>* dec_opt_mr =
00552                         dynamic_cast<CRegistrationDeciderOrOptimizer_MR<GRAPH_T>*>(this->m_optimizer);
00553                 if (dec_opt_mr) {
00554                         dec_opt_mr->setCConnectionManagerPtr(&m_conn_manager);
00555                 }
00556         }
00557         // display messages with the names of the deciders, optimizer and agent string ID
00558         if (this->m_enable_visuals) {
00559                 // NRD
00560                 this->m_win_manager->assignTextMessageParameters(
00561                                 /* offset_y* = */ &m_offset_y_nrd,
00562                                 /* text_index* = */ &m_text_index_nrd);
00563                 this->m_win_manager->addTextMessage(this->m_offset_x_left, -m_offset_y_nrd,
00564                                 mrpt::format("NRD: %s", this->m_node_reg->getClassName().c_str()),
00565                                 TColorf(0,0,0),
00566                                 /* unique_index = */ m_text_index_nrd);
00567 
00568                 // ERD
00569                 this->m_win_manager->assignTextMessageParameters(
00570                                 /* offset_y* = */ &m_offset_y_erd,
00571                                 /* text_index* = */ &m_text_index_erd);
00572                 this->m_win_manager->addTextMessage(
00573                                 this->m_offset_x_left, -m_offset_y_erd,
00574                                 mrpt::format("ERD: %s", this->m_edge_reg->getClassName().c_str()),
00575                                 TColorf(0,0,0),
00576                                 /* unique_index = */ m_text_index_erd);
00577 
00578                 // GSO
00579                 this->m_win_manager->assignTextMessageParameters(
00580                                 /* offset_y* = */ &m_offset_y_gso,
00581                                 /* text_index* = */ &m_text_index_gso);
00582                 this->m_win_manager->addTextMessage(
00583                                 this->m_offset_x_left, -m_offset_y_gso,
00584                                 mrpt::format("GSO: %s", this->m_optimizer->getClassName().c_str()),
00585                                 TColorf(0,0,0),
00586                                 /* unique_index = */ m_text_index_gso);
00587 
00588                 // Agent Namespace
00589                 this->m_win_manager->assignTextMessageParameters(
00590                                 /* offset_y* = */ &m_offset_y_namespace,
00591                                 /* text_index* = */ &m_text_index_namespace);
00592                 this->m_win_manager->addTextMessage(
00593                                 this->m_offset_x_left, -m_offset_y_namespace,
00594                                 mrpt::format("Agent ID: %s", m_conn_manager.getTrimmedNs().c_str()),
00595                                 TColorf(0,0,0),
00596                                 /* unique_index = */ m_text_index_namespace);
00597 
00598         }
00599         this->readParams();
00600 
00601         this->m_optimized_map_color = m_neighbor_colors_manager.getNextTColor();
00602 
00603         // start the spinner for asynchronously servicing cm_graph requests
00604         cm_graph_async_spinner.start();
00605 } // end of initClass
00606 
00607 template<class GRAPH_T>
00608 mrpt::poses::CPose3D CGraphSlamEngine_MR<GRAPH_T>::
00609 getLSPoseForGridMapVisualization(
00610                 const TNodeID nodeID) const {
00611         MRPT_START;
00612         using namespace mrpt::graphs::detail;
00613 
00614         // if this is my own node ID return the corresponding CPose2D, otherwise
00615         // return the pose connecting own graph with the neighbor's graph
00616 
00617         const TMRSlamNodeAnnotations* node_annots = dynamic_cast<const TMRSlamNodeAnnotations*>(
00618                         &this->m_graph.nodes.at(nodeID));
00619 
00620         // Is the current nodeID registered by a neighboring agent or is it my own?
00621         TNeighborAgentProps* neighbor = NULL;
00622         this->getNeighborByAgentID(node_annots->agent_ID_str, neighbor);
00623 
00624         CPose3D laser_pose;
00625         if (!neighbor) { // own node
00626                 laser_pose = parent_t::getLSPoseForGridMapVisualization(nodeID);
00627         }
00628         else { // not by me - return TF to neighbor graph
00629                 laser_pose = CPose3D(neighbor->tf_self_to_neighbor_first_integrated_pose);
00630         }
00631         return laser_pose;
00632 
00633         MRPT_END;
00634 }
00635 
00636 template<class GRAPH_T>
00637 bool CGraphSlamEngine_MR<GRAPH_T>::
00638 getNeighborByAgentID(const std::string& agent_ID_str,
00639                 TNeighborAgentProps*& neighbor) const {
00640         MRPT_START;
00641 
00642         bool ret= false;
00643         for (auto neighbors_it = m_neighbors.begin();
00644                         neighbors_it != m_neighbors.end();
00645                         ++neighbors_it) {
00646 
00647                 if ((*neighbors_it)->getAgentNs() == agent_ID_str) {
00648                         ret = true;
00649                         neighbor = *neighbors_it;
00650                         break;
00651                 }
00652         }
00653 
00654         return ret;
00655         MRPT_END;
00656 }
00657 
00658 template<class GRAPH_T>
00659 void CGraphSlamEngine_MR<GRAPH_T>::usePublishersBroadcasters() {
00660         MRPT_START;
00661         using namespace mrpt_bridge;
00662         using namespace mrpt_msgs;
00663         using namespace std;
00664         using namespace mrpt::math;
00665         using ::operator==;
00666 
00667         // call the parent class
00668         parent_t::usePublishersBroadcasters();
00669 
00670         // update list of neighbors that the current agent can communicate with.
00671         mrpt_msgs::GraphSlamAgents nearby_slam_agents;
00672         m_conn_manager.getNearbySlamAgents(
00673                                 &nearby_slam_agents,
00674                                 /*ignore_self = */ true);
00675         m_list_neighbors_pub.publish(nearby_slam_agents);
00676 
00677         // Initialize TNeighborAgentProps
00678         // for each *new* GraphSlamAgent we should add a TNeighborAgentProps instance,
00679         // and initialize its subscribers so that we fetch every new LaserScan and list of
00680         // modified nodes it publishes
00681         {
00682                 for (GraphSlamAgents::_list_type::const_iterator
00683                                 it = nearby_slam_agents.list.begin();
00684                                 it != nearby_slam_agents.list.end();
00685                                 ++it) {
00686 
00687                         const GraphSlamAgent& gsa = *it;
00688 
00689                         // Is the current GraphSlamAgent already registered?
00690                         const auto search = [gsa](const TNeighborAgentProps* neighbor) {
00691                                 return (neighbor->agent == gsa);
00692                         };
00693                         typename neighbors_t::const_iterator neighbor_it = find_if(
00694                                         m_neighbors.begin(),
00695                                         m_neighbors.end(), search);
00696 
00697                         if (neighbor_it == m_neighbors.end()) { // current gsa not found, add it
00698 
00699                                 MRPT_LOG_DEBUG_STREAM("Initializing NeighborAgentProps instance for "
00700                                         << gsa.name.data);
00701                                 m_neighbors.push_back(new TNeighborAgentProps(*this, gsa));
00702                                 TNeighborAgentProps* latest_neighbor = m_neighbors.back();
00703                                 latest_neighbor->setTColor(m_neighbor_colors_manager.getNextTColor());
00704                                 m_neighbor_to_found_initial_tf.insert(make_pair(
00705                                                         latest_neighbor, false));
00706                                 latest_neighbor->setupComm();
00707                         }
00708                 }
00709         }
00710 
00711         this->pubUpdatedNodesList();
00712         this->pubLastRegdIDScan();
00713 
00714         MRPT_END;
00715 } // end of usePublishersBroadcasters
00716 
00717 template<class GRAPH_T>
00718 bool CGraphSlamEngine_MR<GRAPH_T>::pubUpdatedNodesList() {
00719         MRPT_START;
00720         using namespace mrpt_msgs;
00721 
00722         // update the last X NodeIDs + positions; Do it only when a new node is inserted.
00723         // notified of this change anyway after a new node addition
00724         if (this->m_graph_nodes_last_size == this->m_graph.nodes.size()) {
00725                 return false;
00726         }
00727         MRPT_LOG_DEBUG_STREAM("Updating list of node poses");
00728 
00729         // send at most m_num_last_rgd_nodes
00730         typename GRAPH_T::global_poses_t poses_to_send;
00731         int poses_counter = 0;
00732         // fill the NodeIDWithPose_vec msg
00733         NodeIDWithPose_vec ros_nodes;
00734 
00735         // send up to num_last_regd_nodes Nodes - start from end.
00736         for (typename GRAPH_T::global_poses_t::const_reverse_iterator
00737                         cit = this->m_graph.nodes.rbegin();
00738                         (poses_counter <= m_opts.num_last_regd_nodes &&
00739                          cit != this->m_graph.nodes.rend());
00740                         ++cit) {
00741 
00742                 // Do not resend nodes of others, registered in own graph.
00743                 if (cit->second.agent_ID_str != m_conn_manager.getTrimmedNs()) {
00744                         continue; // skip this.
00745                 }
00746 
00747                 NodeIDWithPose curr_node_w_pose;
00748                 // send basics - NodeID, Pose
00749                 curr_node_w_pose.nodeID = cit->first;
00750                 mrpt_bridge::convert(cit->second, curr_node_w_pose.pose);
00751 
00752                 // send mr-fields
00753                 curr_node_w_pose.str_ID.data = cit->second.agent_ID_str;
00754                 curr_node_w_pose.nodeID_loc = cit->second.nodeID_loc;
00755 
00756                 ros_nodes.vec.push_back(curr_node_w_pose);
00757 
00758                 poses_counter++;
00759         }
00760 
00761         m_last_regd_nodes_pub.publish(ros_nodes);
00762 
00763         // update the last known size
00764         m_graph_nodes_last_size = this->m_graph.nodeCount();
00765 
00766         bool res = false;
00767         if (poses_counter) {
00768                 res = true;
00769         }
00770 
00771         return res;
00772         MRPT_END;
00773 } // end of pubUpdatedNodesList
00774 
00775 template<class GRAPH_T>
00776 bool CGraphSlamEngine_MR<GRAPH_T>::pubLastRegdIDScan() {
00777         MRPT_START;
00778         using namespace mrpt_msgs;
00779         using namespace mrpt_bridge;
00780 
00781         // Update the last registered scan + associated nodeID
00782         // Last registered scan always corresponds to the *last* element of the of the
00783         // published NodeIDWithPose_vec that is published above.
00784         //
00785         // - Check if map is empty
00786         // - Have I already published the last laser scan?
00787         if (!this->m_nodes_to_laser_scans2D.empty() &&
00788                         m_nodes_to_laser_scans2D_last_size < this->m_nodes_to_laser_scans2D.size()) {
00789                 // last registered scan
00790                 MRPT_NodeIDWithLaserScan mrpt_last_regd_id_scan =
00791                         *(this->m_nodes_to_laser_scans2D.rbegin());
00792 
00793 
00794                 // if this is a mr-registered nodeID+LS, skip it.
00795                 if (!this->isOwnNodeID(mrpt_last_regd_id_scan.first)) {
00796                         return false;
00797                 }
00798 
00799                 //MRPT_LOG_DEBUG_STREAM
00800                         //<< "Publishing LaserScan of nodeID \""
00801                         //<< mrpt_last_regd_id_scan.first << "\"";
00802                 ASSERT_(mrpt_last_regd_id_scan.second);
00803 
00804                 // convert to ROS msg
00805                 mrpt_msgs::NodeIDWithLaserScan ros_last_regd_id_scan;
00806                 convert(*(mrpt_last_regd_id_scan.second), ros_last_regd_id_scan.scan);
00807                 ros_last_regd_id_scan.nodeID = mrpt_last_regd_id_scan.first;
00808 
00809                 m_last_regd_id_scan_pub.publish(ros_last_regd_id_scan);
00810 
00811                 // update the last known size.
00812                 m_nodes_to_laser_scans2D_last_size =
00813                         this->m_nodes_to_laser_scans2D.size();
00814 
00815                 return true;
00816         }
00817         else {
00818                 return false;
00819         }
00820 
00821 
00822         MRPT_END;
00823 } // end of pubLastRegdIDScan
00824 
00825 
00826 template<class GRAPH_T>
00827 bool CGraphSlamEngine_MR<GRAPH_T>::isOwnNodeID(
00828                 const TNodeID nodeID,
00829                 const global_pose_t* pose_out/*=NULL*/) const {
00830         MRPT_START;
00831         using namespace mrpt::graphs::detail;
00832 
00833         // make sure give node is in the graph
00834         typename GRAPH_T::global_poses_t::const_iterator global_pose_search =
00835                 this->m_graph.nodes.find(nodeID);
00836         ASSERTMSG_(global_pose_search != this->m_graph.nodes.end(),
00837                         mrpt::format(
00838                                 "isOwnNodeID called for nodeID \"%lu\" which is not found in the graph",
00839                                 static_cast<unsigned long>(nodeID)));
00840 
00841         // fill pointer to global_pose_t
00842         if (pose_out) {
00843                 pose_out = &global_pose_search->second;
00844         }
00845 
00846         bool res = false;
00847         const TMRSlamNodeAnnotations* node_annots = dynamic_cast<const TMRSlamNodeAnnotations*>(
00848                         &global_pose_search->second);
00849         if ((node_annots && node_annots->agent_ID_str == m_conn_manager.getTrimmedNs()) ||
00850                         (!node_annots)) {
00851                 res = true;
00852         }
00853 
00854         return res;
00855 
00856         MRPT_END;
00857 } // end of isOwnNodeID
00858 
00859 template<class GRAPH_T>
00860 void CGraphSlamEngine_MR<GRAPH_T>::readParams() {
00861         using namespace mrpt::utils;
00862         using namespace mrpt::slam;
00863 
00864         this->readROSParameters();
00865 
00866         // GridMap Alignment
00867         m_alignment_options.loadFromConfigFileName(this->m_config_fname, m_sec_alignment_params);
00868 
00869         // Thu Jun 8 17:02:17 EEST 2017, Nikos Koukis
00870         // other option ends up in segfault.
00871         m_alignment_options.methodSelection = CGridMapAligner::amModifiedRANSAC;
00872 
00873         m_opts.loadFromConfigFileName(this->m_config_fname, m_sec_mr_slam_params);
00874 } // end of readParams
00875 
00876 template<class GRAPH_T>
00877 void CGraphSlamEngine_MR<GRAPH_T>::readROSParameters() {
00878         // call parent method first in case the parent wants to ask for any ROS
00879         // parameters
00880         parent_t::readROSParameters();
00881 
00882 }
00883 
00884 template<class GRAPH_T>
00885 void CGraphSlamEngine_MR<GRAPH_T>::printParams() const {
00886         parent_t::printParams();
00887         m_alignment_options.dumpToConsole();
00888         m_opts.dumpToConsole();
00889 }
00890 
00891 
00892 
00893 template<class GRAPH_T>
00894 void CGraphSlamEngine_MR<GRAPH_T>::setupSubs() { }
00895 
00896 template<class GRAPH_T>
00897 void CGraphSlamEngine_MR<GRAPH_T>::setupPubs() {
00898         using namespace mrpt_msgs;
00899         using namespace sensor_msgs;
00900 
00901         m_list_neighbors_pub = m_nh->advertise<GraphSlamAgents>(
00902                         m_list_neighbors_topic,
00903                         this->m_queue_size,
00904                         /*latch = */ true);
00905 
00906         // last registered laser scan - by default this corresponds to the last
00907         // nodeID of the vector of last registered nodes.
00908         m_last_regd_id_scan_pub = m_nh->advertise<NodeIDWithLaserScan>(
00909                         m_last_regd_id_scan_topic,
00910                         this->m_queue_size,
00911                         /*latch = */ true);
00912 
00913         // last X nodeIDs + positions
00914         m_last_regd_nodes_pub = m_nh->advertise<NodeIDWithPose_vec>(
00915                         m_last_regd_nodes_topic,
00916                         this->m_queue_size,
00917                         /*latch = */ true);
00918 
00919 
00920 
00921 }
00922 
00923 template<class GRAPH_T>
00924 void CGraphSlamEngine_MR<GRAPH_T>::setupSrvs() {
00925         // cm_graph service requests are handled by the custom custom_service_queue CallbackQueue
00926         ros::CallbackQueueInterface* global_queue = m_nh->getCallbackQueue();
00927         m_nh->setCallbackQueue(&this->custom_service_queue);
00928 
00929         m_cm_graph_srvserver = m_nh->advertiseService(
00930                         m_cm_graph_service,
00931                         &CGraphSlamEngine_MR<GRAPH_T>::getCMGraph, this);
00932 
00933         m_nh->setCallbackQueue(global_queue);
00934 }
00935 
00936 template<class GRAPH_T>
00937 bool CGraphSlamEngine_MR<GRAPH_T>::getCMGraph(
00938                 mrpt_msgs::GetCMGraph::Request& req,
00939                 mrpt_msgs::GetCMGraph::Response& res) {
00940         using namespace std;
00941         using namespace mrpt::utils;
00942         using namespace mrpt::math;
00943 
00944         set<TNodeID> nodes_set(req.nodeIDs.begin(), req.nodeIDs.end());
00945         MRPT_LOG_INFO_STREAM("Called the GetCMGraph service for nodeIDs: "
00946                 << getSTLContainerAsString(nodes_set));
00947 
00948         if (nodes_set.size() < 2) { return false; }
00949 
00950         // fill the given Response with the ROS NetworkOfPoses
00951         GRAPH_T mrpt_subgraph;
00952         this->m_graph.extractSubGraph(nodes_set, &mrpt_subgraph,
00953                         /*root_node = */ INVALID_NODEID,
00954                         /*auto_expand_set=*/false);
00955         mrpt_bridge::convert(mrpt_subgraph, res.cm_graph);
00956         return true;
00957 } // end of getCMGraph
00958 
00959 template<class GRAPH_T>
00960 void CGraphSlamEngine_MR<GRAPH_T>::setObjectPropsFromNodeID(
00961                 const TNodeID  nodeID,
00962                 mrpt::opengl::CSetOfObjects::Ptr& viz_object) {
00963         using namespace mrpt::utils;
00964         MRPT_START;
00965 
00966         // who registered this node?
00967         TNeighborAgentProps* neighbor = NULL;
00968         std::string& agent_ID_str = this->m_graph.nodes.at(nodeID).agent_ID_str;
00969         bool is_not_own = getNeighborByAgentID(agent_ID_str, neighbor);
00970 
00971         TColor obj_color;
00972         if (!is_not_own) { // I registered this.
00973                 // use the standard maps color
00974                 obj_color = this->m_optimized_map_color;
00975         }
00976         else {
00977                 ASSERT_(neighbor);
00978                 obj_color = neighbor->color;
00979         }
00980         viz_object->setColor_u8(obj_color);
00981 
00982         MRPT_END;
00983 }// end of setObjectPropsFromNodeID
00984 
00985 
00986 template<class GRAPH_T>
00987 void CGraphSlamEngine_MR<GRAPH_T>::monitorNodeRegistration(
00988                 bool registered/*=false*/,
00989                 std::string class_name/*="Class"*/) {
00990         MRPT_START;
00991         using namespace mrpt::utils;
00992 
00993         if (m_registered_multiple_nodes) {
00994                 MRPT_LOG_ERROR_STREAM("m_registered_multiple_nodes = TRUE!");
00995                 m_registered_multiple_nodes = !m_registered_multiple_nodes;
00996                 this->m_nodeID_max = this->m_graph.nodeCount()-1;
00997         }
00998         else {
00999                 parent_t::monitorNodeRegistration(registered, class_name);
01000         }
01001 
01002         MRPT_END;
01003 } // end of monitorNodeRegistration
01004 
01005 template<class GRAPH_T>
01006 void CGraphSlamEngine_MR<GRAPH_T>::getRobotEstimatedTrajectory(
01007                 typename GRAPH_T::global_poses_t* graph_poses) const {
01008         MRPT_START;
01009         ASSERT_(graph_poses);
01010 
01011         for (const auto& n : this->m_graph.nodes) {
01012                 if (n.second.agent_ID_str == m_conn_manager.getTrimmedNs()) {
01013                         graph_poses->insert(n);
01014                 }
01015         }
01016 
01017         MRPT_END;
01018 } // end of getRobotEstimatedTrajectory
01019 
01020 template<class GRAPH_T>
01021 void CGraphSlamEngine_MR<GRAPH_T>::
01022 getAllOwnNodes(std::set<TNodeID>* nodes_set) const {
01023         ASSERT_(nodes_set);
01024         nodes_set->clear();
01025 
01026         for (const auto& n : this->m_graph.nodes) {
01027                 if (n.second.agent_ID_str == m_conn_manager.getTrimmedNs()) {
01028                         nodes_set->insert(n.first);
01029                 }
01030         }
01031 } // end of getAllOwnNodes
01032 
01033 template<class GRAPH_T>
01034 void CGraphSlamEngine_MR<GRAPH_T>::
01035 getNodeIDsOfEstimatedTrajectory(
01036                 std::set<TNodeID>* nodes_set) const {
01037         ASSERT_(nodes_set);
01038         this->getAllOwnNodes(nodes_set);
01039 } // end of getNodeIDsOfEstimatedTrajectory
01040 
01042 
01043 template<class GRAPH_T>
01044 CGraphSlamEngine_MR<GRAPH_T>::TNeighborAgentProps::TNeighborAgentProps(
01045                 CGraphSlamEngine_MR<GRAPH_T>& engine_in,
01046                 const mrpt_msgs::GraphSlamAgent& agent_in):
01047         engine(engine_in),
01048         agent(agent_in),
01049         has_setup_comm(false)
01050 {
01051         using namespace mrpt::utils;
01052 
01053         nh = engine.m_nh;
01054         m_queue_size = engine.m_queue_size;
01055         this->resetFlags();
01056 
01057         // fill the full paths of the topics to subscribe
01058         // ASSUMPTION: agents namespaces start at the root "/"
01059         this->last_regd_nodes_topic = "/" + agent.topic_namespace.data + "/" +
01060                 engine.m_last_regd_nodes_topic;
01061         this->last_regd_id_scan_topic = "/" + agent.topic_namespace.data + "/" +
01062                 engine.m_last_regd_id_scan_topic;
01063         this->cm_graph_service = "/" + agent.topic_namespace.data + "/" +
01064                 engine.m_cm_graph_service;
01065 
01066         engine.logFmt(LVL_DEBUG,
01067                         "In constructor of TNeighborAgentProps for topic namespace: %s",
01068                         agent.topic_namespace.data.c_str());
01069 
01070         // initialize the occupancy map based on the engine's gridmap properties
01071   gridmap_cached = mrpt::maps::COccupancyGridMap2D::Create();
01072         COccupancyGridMap2D::Ptr eng_gridmap = engine.m_gridmap_cached;
01073         gridmap_cached->setSize(
01074                         eng_gridmap->getXMin(),
01075                         eng_gridmap->getXMax(),
01076                         eng_gridmap->getYMin(),
01077                         eng_gridmap->getYMax(),
01078                         eng_gridmap->getResolution());
01079 
01080 } // TNeighborAgentProps::TNeighborAgentProps
01081 
01082 template<class GRAPH_T>
01083 CGraphSlamEngine_MR<GRAPH_T>::TNeighborAgentProps::~TNeighborAgentProps() { }
01084 
01085 template<class GRAPH_T>
01086 void CGraphSlamEngine_MR<GRAPH_T>::TNeighborAgentProps::setupComm() {
01087         using namespace mrpt::utils;
01088 
01089         this->setupSubs();
01090         this->setupSrvs();
01091 
01092         engine.logFmt(
01093                         LVL_DEBUG,
01094                         "TNeighborAgentProps: Successfully set up subscribers/services "
01095                         "to agent topics for namespace [%s].",
01096                         agent.topic_namespace.data.c_str());
01097 
01098         has_setup_comm = true;
01099 }
01100 
01101 template<class GRAPH_T>
01102 void CGraphSlamEngine_MR<GRAPH_T>::TNeighborAgentProps::setupSrvs() {
01103 
01104         cm_graph_srvclient =
01105                 nh->serviceClient<mrpt_msgs::GetCMGraph>(cm_graph_service);
01106 }
01107 
01108 
01109 template<class GRAPH_T>
01110 void CGraphSlamEngine_MR<GRAPH_T>::TNeighborAgentProps::setupSubs() {
01111         using namespace mrpt_msgs;
01112         using namespace mrpt::utils;
01113 
01114         last_regd_nodes_sub = nh->subscribe<NodeIDWithPose_vec>(
01115                         last_regd_nodes_topic,
01116                         m_queue_size,
01117                         &TNeighborAgentProps::fetchUpdatedNodesList, this);
01118         last_regd_id_scan_sub = nh->subscribe<NodeIDWithLaserScan>(
01119                         last_regd_id_scan_topic,
01120                         m_queue_size,
01121                         &TNeighborAgentProps::fetchLastRegdIDScan, this);
01122 }
01123 
01124 template<class GRAPH_T>
01125 void CGraphSlamEngine_MR<GRAPH_T>::TNeighborAgentProps::
01126 fetchUpdatedNodesList(
01127                 const mrpt_msgs::NodeIDWithPose_vec::ConstPtr& nodes) {
01128         MRPT_START;
01129         using namespace mrpt_msgs;
01130         using namespace mrpt_bridge;
01131         using namespace std;
01132         using namespace mrpt::utils;
01133 
01134         typedef typename GRAPH_T::constraint_t::type_value pose_t;
01135         engine.logFmt(LVL_DEBUG, "In fetchUpdatedNodesList method.");
01136 
01137         for (NodeIDWithPose_vec::_vec_type::const_iterator
01138                         n_it = nodes->vec.begin();
01139                         n_it != nodes->vec.end();
01140                         ++n_it) {
01141 
01142                 // insert in the set if not already there.
01143                 TNodeID  nodeID = static_cast<TNodeID>(n_it->nodeID);
01144                 std::pair<set<TNodeID>::iterator, bool> res =
01145                         nodeIDs_set.insert(nodeID);
01146                 // if I just inserted this node mark it as not used (in own graph)
01147                 if (res.second) { // insertion took place.
01148                         engine.logFmt(LVL_INFO, "Just fetched a new nodeID: %lu",
01149                                         static_cast<unsigned long>(nodeID));
01150                         nodeID_to_is_integrated.insert(make_pair(n_it->nodeID, false));
01151                 }
01152 
01153                 // update the poses
01154                 pose_t curr_pose;
01155                 // note: use "operator[]" instead of "insert" so that if the key already
01156                 // exists, the corresponding value is changed rather than ignored.
01157                 poses[static_cast<TNodeID>(n_it->nodeID)] =
01158                         convert(n_it->pose, curr_pose);
01159         }
01160   has_new_nodes = true;
01161 
01163         // TODO When using 3 graphSLAM agents GDB Shows that it crashes on
01164         // engine.logFmt lines. Fix this.
01165         //
01166   //engine.logFmt(LVL_DEBUG, // THIS CRASHES - GDB WHERE
01167           //"NodeIDs for topic namespace: %s -> [%s]",
01168           //agent.topic_namespace.data.c_str(),
01169           //mrpt::math::getSTLContainerAsString(vector<TNodeID>(
01170                   //nodeIDs_set.begin(), nodeIDs_set.end())).c_str());
01171   // print poses just for verification
01172   //engine.logFmt(LVL_DEBUG, "Poses for topic namespace: %s",
01173           //agent.topic_namespace.data.c_str());
01174   //for (typename GRAPH_T::global_poses_t::const_iterator
01175           //p_it = poses.begin();
01176           //p_it != poses.end();
01177           //++p_it) {
01178         //std::string p_str; p_it->second.asString(p_str);
01179         //engine.logFmt(LVL_DEBUG, "nodeID: %lu | pose: %s",
01180                 //static_cast<unsigned long>(p_it->first),
01181                 //p_str.c_str());
01182   //}
01183         // TODO - These also seem to crash sometimes
01184         //cout << "Agent information: " << agent << endl;
01185         //cout << "Nodes: " << mrpt::math::getSTLContainerAsString(vector<TNodeID>(nodeIDs_set.begin(), nodeIDs_set.end()));
01186   //print nodeIDs just for verification
01187 
01188   MRPT_END;
01189 } // end of fetchUpdatedNodesList
01190 
01191 template<class GRAPH_T>
01192 void CGraphSlamEngine_MR<GRAPH_T>::TNeighborAgentProps::
01193 fetchLastRegdIDScan(
01194                 const mrpt_msgs::NodeIDWithLaserScan::ConstPtr& last_regd_id_scan) {
01195         MRPT_START;
01196         using namespace std;
01197         using namespace mrpt::utils;
01198         ASSERT_(last_regd_id_scan);
01199   engine.logFmt(LVL_DEBUG, "In fetchLastRegdIDScan method.");
01200 
01201         // Pose may not be available due to timing in publishing of the corresponding
01202         // topics. Just keep it in ROS form and then convert them to MRPT form when
01203         // needed.
01204         ros_scans.push_back(*last_regd_id_scan);
01205         has_new_scans = true;
01206 
01207         MRPT_END;
01208 } // end of fetchLastRegdIDScan
01209 
01210 template<class GRAPH_T>
01211 void CGraphSlamEngine_MR<GRAPH_T>::TNeighborAgentProps::getCachedNodes(
01212                 std::vector<TNodeID>* nodeIDs/*=NULL*/,
01213                 std::map<
01214                         TNodeID,
01215                         node_props_t>* nodes_params/*=NULL*/,
01216                 bool only_unused/*=true*/) const {
01217         MRPT_START;
01218         using namespace mrpt::obs;
01219         using namespace mrpt::utils;
01220         using namespace mrpt::math;
01221         using namespace std;
01222         using namespace mrpt::poses;
01223 
01224         // at least one of the two args should be given.
01225         ASSERT_(nodeIDs || nodes_params);
01226 
01227         // traverse all nodes
01228         for (std::set<TNodeID>::const_iterator
01229                         n_it = nodeIDs_set.begin();
01230                         n_it != nodeIDs_set.end();
01231                         ++n_it) {
01232 
01233                 // Should I return only the unused ones?
01234                 // If so, if the current nodeID is integrated, skip it.
01235                 if (only_unused && nodeID_to_is_integrated.at(*n_it)) { continue; }
01236 
01237                 // add the node properties
01238                 if (nodes_params) {
01239                         std::pair<TNodeID, node_props_t> params; // current pair to be inserted.
01240                         const pose_t* p = &poses.at(*n_it);
01241 
01242                         params.first = *n_it;
01243                         params.second.pose = *p;
01244                         CObservation2DRangeScan::Ptr mrpt_scan = CObservation2DRangeScan::Create();
01245           const sensor_msgs::LaserScan* ros_laser_scan =
01246                 this->getLaserScanByNodeID(*n_it);
01247 
01248       // if LaserScan not found, skip nodeID altogether.
01249       //
01250       // Its natural to have more poses than LaserScans since on every node
01251       // registration I send a modified list of X node positions and just one
01252       // LaserScan
01253           if (!ros_laser_scan) { continue; }
01254 
01255                         mrpt_bridge::convert(*ros_laser_scan, CPose3D(*p), *mrpt_scan);
01256                         params.second.scan = mrpt_scan;
01257 
01258                         // insert the pair
01259                         nodes_params->insert(params);
01260 
01261                         // debugging message
01262                         //std::stringstream ss;
01263                         //ss << "\ntID: " << nodes_params->rbegin()->first
01264                                 //<< " ==> Props: " << nodes_params->rbegin()->second;
01265                         //engine.logFmt(LVL_DEBUG, "%s", ss.str().c_str());
01266                 }
01267 
01268                 // add the nodeID
01269                 if (nodeIDs) {
01270                         // do not return nodeIDs that don't have valid laserScans
01271                         // this is also checked at the prior if
01272                         if (!nodes_params && !this->getLaserScanByNodeID(*n_it)) {
01273                                 continue;
01274                         }
01275 
01276                         nodeIDs->push_back(*n_it);
01277                 }
01278         }
01279 
01280         MRPT_END;
01281 } // end of TNeighborAgentProps::getCachedNodes
01282 
01283 template<class GRAPH_T>
01284 void CGraphSlamEngine_MR<GRAPH_T>::TNeighborAgentProps::resetFlags() const {
01285   has_new_nodes = false;
01286   has_new_scans = false;
01287 
01288 }
01289 
01290 template<class GRAPH_T>
01291 bool CGraphSlamEngine_MR<GRAPH_T>::TNeighborAgentProps::
01292 hasNewNodesBatch(int new_batch_size) {
01293         MRPT_START;
01294 
01295         auto is_not_integrated = [this](const std::pair<TNodeID, bool> pair) {
01296                 return (pair.second == false && getLaserScanByNodeID(pair.first));
01297         };
01298         int not_integrated_num = count_if(
01299                         nodeID_to_is_integrated.begin(),
01300                         nodeID_to_is_integrated.end(),
01301                         is_not_integrated);
01302 
01303         return (not_integrated_num >= new_batch_size);
01304 
01305         MRPT_END;
01306 }
01307 
01308 
01309 template<class GRAPH_T>
01310 const sensor_msgs::LaserScan*
01311 CGraphSlamEngine_MR<GRAPH_T>::TNeighborAgentProps::
01312 getLaserScanByNodeID(
01313                 const TNodeID nodeID) const {
01314         MRPT_START;
01315 
01316         // assert that the current nodeID exists in the nodeIDs_set
01317         ASSERT_(nodeIDs_set.find(nodeID) != nodeIDs_set.end());
01318 
01319         for (std::vector<mrpt_msgs::NodeIDWithLaserScan>::const_iterator
01320                         it = ros_scans.begin();
01321                         it != ros_scans.end();
01322                         ++it) {
01323                 if (it->nodeID == nodeID) {
01324                         return &it->scan;
01325                 }
01326         }
01327 
01328         // if out here, LaserScan doesn't exist.
01329   return 0;
01330   MRPT_END;
01331 } // end of TNeighborAgentProps::getLaserScanByNodeID
01332 
01333 template<class GRAPH_T>
01334 void
01335 CGraphSlamEngine_MR<GRAPH_T>::TNeighborAgentProps::fillOptPaths(
01336                 const std::set<TNodeID>& nodeIDs,
01337                 paths_t* opt_paths) const {
01338         MRPT_START;
01339         using namespace std;
01340         using namespace mrpt::utils;
01341         typedef std::set<TNodeID>::const_iterator set_cit;
01342 
01343         // make sure that all given nodes belong in the nodeIDs_set.
01344         ASSERTMSG_(includes(nodeIDs_set.begin(), nodeIDs_set.end(),
01345                                 nodeIDs.begin(), nodeIDs.end()),
01346                         "nodeIDs is not a strict subset of the current neighbor's nodes");
01347         ASSERT_(opt_paths);
01348 
01349         for (set_cit cit = nodeIDs.begin();
01350                         cit != std::prev(nodeIDs.end());
01351                         ++cit) {
01352 
01353                 for (set_cit cit2 = std::next(cit);
01354                                 cit2 != nodeIDs.end();
01355                                 ++cit2) {
01356 
01357 
01358                         constraint_t c = constraint_t(poses.at(*cit2) - poses.at(*cit));
01359                         c.cov_inv =
01360                                 mrpt::math::CMatrixFixedNumeric<double,
01361                                         constraint_t::state_length,
01362                                         constraint_t::state_length>();
01363                         c.cov_inv.unit();
01364                         c.cov_inv *= 500;
01365 
01366                         opt_paths->push_back(path_t(
01367                                                 /*start=*/ *cit,
01368                                                 /*end=*/ *cit2,
01369                                                 /*constraint=*/ c));
01370 
01371                         engine.logFmt(LVL_DEBUG,
01372                                         "Filling optimal path for nodes: %lu => %lu: %s",
01373                                         static_cast<unsigned long>(*cit),
01374                                         static_cast<unsigned long>(*cit2),
01375                                         opt_paths->back().curr_pose_pdf.getMeanVal().asString().c_str());
01376 
01377                 }
01378         }
01379         MRPT_END;
01380 } // end of TNeighborAgentProps::fillOptPaths
01381 
01382 template<class GRAPH_T>
01383 void CGraphSlamEngine_MR<GRAPH_T>::TNeighborAgentProps::
01384 computeGridMap() const {
01385         MRPT_START;
01386         using namespace mrpt::poses;
01387         using namespace mrpt::utils;
01388         using namespace mrpt;
01389         using namespace mrpt::math;
01390         using namespace std;
01391 
01392         gridmap_cached->clear();
01393 
01394         std::vector<TNodeID> nodeIDs;
01395         std::map<TNodeID, node_props_t> nodes_params;
01396         // get list of nodes, laser scans
01397         this->getCachedNodes(&nodeIDs, &nodes_params, false);
01398 
01399         // iterate over poses, scans. Add them to the gridmap.
01400         for (typename map<TNodeID, node_props_t>::const_iterator
01401                         it = nodes_params.begin();
01402                         it != nodes_params.end();
01403                         ++it) {
01404                 const CPose3D curr_pose_3d; // do not add the actual pose!
01405                 gridmap_cached->insertObservation(it->second.scan.get(), &curr_pose_3d);
01406         }
01407 
01408         MRPT_END;
01409 } // end of TNeighborAgentProps::computeGridMap
01410 
01411 template<class GRAPH_T>
01412 const mrpt::maps::COccupancyGridMap2D::Ptr&
01413 CGraphSlamEngine_MR<GRAPH_T>::TNeighborAgentProps::
01414 getGridMap() const {
01415         MRPT_START;
01416         if (hasNewData()) {
01417                 this->computeGridMap();
01418         }
01419 
01420         return gridmap_cached;
01421         MRPT_END;
01422 } // end of TNeighborAgentProps::getGridMap
01423 
01424 template<class GRAPH_T>
01425 void CGraphSlamEngine_MR<GRAPH_T>::TNeighborAgentProps::
01426 getGridMap(mrpt::maps::COccupancyGridMap2D::Ptr& map) const {
01427         MRPT_START;
01428         ASSERT_(map);
01429 
01430         if (hasNewData()) {
01431                 this->computeGridMap();
01432         }
01433 
01434         map->copyMapContentFrom(*gridmap_cached);
01435         MRPT_END;
01436 } // end of TNeighborAgentProps::getGridMap
01437 
01438 
01439 template<class GRAPH_T>
01440 bool CGraphSlamEngine_MR<GRAPH_T>::TNeighborAgentProps::hasNewData() const {
01441   return has_new_nodes && has_new_scans;
01442 } // end of hasNewData
01443 
01444 template<class GRAPH_T>
01445 CGraphSlamEngine_MR<GRAPH_T>::TOptions::TOptions(const engine_mr_t& engine_in):
01446         conservative_find_initial_tfs_to_neighbors(false),
01447         nodes_integration_batch_size(4),
01448         num_last_regd_nodes(10),
01449         inter_group_node_count_thresh(40),
01450         inter_group_node_count_thresh_minadv(25),
01451         engine(engine_in)
01452 {
01453 } // end of TOptions::TOptions
01454 
01455 template<class GRAPH_T>
01456 CGraphSlamEngine_MR<GRAPH_T>::TOptions::~TOptions() {
01457 } // end of TOptions::~TOptions
01458 
01459 template<class GRAPH_T>
01460 void CGraphSlamEngine_MR<GRAPH_T>::TOptions::loadFromConfigFile(
01461                 const CConfigFileBase& source,
01462                 const std::string& section) {
01463 
01464         MRPT_LOAD_CONFIG_VAR(nodes_integration_batch_size, int, source, section);
01465         MRPT_LOAD_CONFIG_VAR(num_last_regd_nodes, int, source, section);
01466 
01467         MRPT_LOAD_CONFIG_VAR(conservative_find_initial_tfs_to_neighbors, bool, source, section);
01468         ASSERTMSG_(!conservative_find_initial_tfs_to_neighbors,
01469                         "Conservative behavior is not yet implemented.");
01470 
01471 
01472         MRPT_LOAD_CONFIG_VAR(inter_group_node_count_thresh, int, source, section);
01473         // warn user if they choose smaller threshold.
01474         if (inter_group_node_count_thresh < inter_group_node_count_thresh_minadv) {
01475                 engine.logFmt(LVL_ERROR,
01476                                 "inter_group_node_count_thresh [%d]"
01477                                 "is set lower than the advised minimum [%d]",
01478                                 inter_group_node_count_thresh,
01479                                 inter_group_node_count_thresh_minadv);
01480 
01481                 std::this_thread::sleep_for(std::chrono::milliseconds(2000));
01482         }
01483 
01484 
01485 } // end of TOptions::loadFromConfigFile
01486 
01487 template<class GRAPH_T>
01488 void CGraphSlamEngine_MR<GRAPH_T>::TOptions::dumpToTextStream(
01489 #if MRPT_VERSION>=0x199
01490                 std::ostream& out) const {
01491 #else
01492                 mrpt::utils::CStream& out) const {
01493 #endif
01494 
01495         LOADABLEOPTS_DUMP_VAR(nodes_integration_batch_size, int);
01496         LOADABLEOPTS_DUMP_VAR(num_last_regd_nodes, int);
01497         LOADABLEOPTS_DUMP_VAR(conservative_find_initial_tfs_to_neighbors, bool);
01498         LOADABLEOPTS_DUMP_VAR(static_cast<int>(inter_group_node_count_thresh), int)
01499         LOADABLEOPTS_DUMP_VAR(inter_group_node_count_thresh_minadv, int)
01500 
01501 } // end of TOptions::dumpToTextStream
01502 
01503 
01504 
01505 } } // end of namespaces
01506 


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Thu Jun 6 2019 21:40:26