14 #include <mrpt_msgs/GetCMGraph.h> 16 #include <mrpt/ros1bridge/pose.h> 18 #include <mrpt/math/CMatrixFixed.h> 22 template <
typename T, std::
size_t ROWS, std::
size_t COLS>
30 template <
class GRAPH_T>
33 const std::string& rawlog_fname ,
34 const std::string& fname_GT ,
35 mrpt::graphslam::CWindowManager* win_manager ,
36 mrpt::graphslam::deciders::CNodeRegistrationDecider<GRAPH_T>*
38 mrpt::graphslam::deciders::CEdgeRegistrationDecider<GRAPH_T>*
40 mrpt::graphslam::optimizers::CGraphSlamOptimizer<GRAPH_T>*
43 nh, config_file, rawlog_fname, fname_GT, win_manager, node_reg,
45 m_conn_manager(dynamic_cast<
mrpt::system::COutputLogger*>(this), nh),
47 m_graph_nodes_last_size(0),
48 m_registered_multiple_nodes(false),
49 cm_graph_async_spinner( 1, &this->custom_service_queue),
50 m_sec_alignment_params(
"AlignmentParameters"),
51 m_sec_mr_slam_params(
"MultiRobotParameters"),
57 template <
class GRAPH_T>
60 MRPT_LOG_DEBUG_STREAM(
61 "In Destructor: Deleting CGraphSlamEngine_MR instance...");
64 for (
typename neighbors_t::iterator neighbors_it =
m_neighbors.begin();
71 template <
class GRAPH_T>
82 ->tf_self_to_neighbor_first_integrated_pose) &&
84 neighbor->hasNewData() &&
99 template <
class GRAPH_T>
109 std::vector<TNodeID> nodeIDs;
110 std::map<TNodeID, node_props_t> nodes_params;
116 mrpt_msgs::GetCMGraph cm_graph_srv;
119 for (
const auto n : nodeIDs)
121 cm_graph_srv.request.node_ids.push_back(n);
124 MRPT_LOG_DEBUG_STREAM(
"Asking for the graph.");
128 MRPT_LOG_ERROR_STREAM(
"Service call for CM_Graph failed.");
131 MRPT_LOG_DEBUG_STREAM(
"Fetched graph successfully.");
132 MRPT_LOG_DEBUG_STREAM(cm_graph_srv.response.cm_graph);
140 MRPT_LOG_WARN_STREAM(
141 "Merging new batch from \"" 143 <<
"Batch: " << getSTLContainerAsString(cm_graph_srv.request.node_ids));
148 pair<TNodeID, node_props_t> node_props_to_connect =
149 *nodes_params.begin();
153 c.mean = node_props_to_connect.second.pose -
155 c.cov_inv.setIdentity();
156 graph_conn.setEdge(c);
158 graph_conn.from = INVALID_NODEID;
161 for (
const auto n : this->m_graph.nodes)
163 if (n.second.agent_ID_str == neighbor->
getAgentNs() &&
164 n.second.nodeID_loc ==
167 graph_conn.from = n.first;
171 ASSERT_(graph_conn.from != INVALID_NODEID);
172 graph_conn.to = node_props_to_connect.first;
174 MRPT_LOG_DEBUG_STREAM(
175 "Hypothesis for adding the batch of nodes: " << graph_conn);
176 graph_conns.push_back(graph_conn);
179 std::map<TNodeID, TNodeID> old_to_new_mappings;
180 this->m_graph.mergeGraph(
181 other_graph, graph_conns,
182 false, &old_to_new_mappings);
187 MRPT_LOG_WARN_STREAM(
"Marking used nodes as integrated - Integrating LSs");
189 for (
typename std::vector<TNodeID>::const_iterator n_cit = nodeIDs.begin();
190 n_cit != nodeIDs.end(); ++n_cit)
197 new_nodeIDs_to_scans_pairs.insert(make_pair(
198 old_to_new_mappings.at(*n_cit), nodes_params.at(*n_cit).scan));
199 MRPT_LOG_INFO_STREAM(
200 "Adding nodeID-LS of nodeID: " 201 <<
"\t[old:] " << *n_cit << endl
202 <<
"| [new:] " << old_to_new_mappings.at(*n_cit));
205 this->m_nodes_to_laser_scans2D.insert(
206 new_nodeIDs_to_scans_pairs.begin(), new_nodeIDs_to_scans_pairs.end());
210 this->execDijkstraNodesEstimation();
215 TNodeID last_node = *nodeIDs.rbegin();
217 make_pair(last_node, nodes_params.at(last_node).pose);
224 template <
class GRAPH_T>
239 bool ret_val =
false;
242 for (
typename neighbors_t::iterator neighbors_it =
m_neighbors.begin();
252 MRPT_LOG_DEBUG_STREAM(
253 "Updating own cached map after successful node " 270 template <
class GRAPH_T>
281 bool ret_val =
false;
283 std::vector<TNodeID> neighbor_nodes;
284 std::map<TNodeID, node_props_t> nodes_params;
286 &neighbor_nodes, &nodes_params,
297 COccupancyGridMap2D::Ptr neighbor_gridmap = neighbor->
getGridMap();
298 CGridMapAligner gridmap_aligner;
301 CGridMapAligner::TReturnInfo results;
304 CPosePDFGaussian init_estim;
307 LVL_INFO,
"Trying to align the maps, initial estimation: %s",
308 init_estim.mean.asString().c_str());
317 TMetricMapAlignmentResult alignRes;
319 const CPosePDF::Ptr pdf_tmp = gridmap_aligner.AlignPDF(
320 this->m_gridmap_cached.get(), neighbor_gridmap.get(), init_estim,
323 const auto run_time = alignRes.executionTime;
325 this->logFmt(LVL_INFO,
"Elapsed Time: %f", run_time);
326 CPosePDFSOG::Ptr pdf_out = CPosePDFSOG::Create();
327 pdf_out->copyFrom(*pdf_tmp);
330 CMatrixDouble33 cov_out;
331 pdf_out->getMostLikelyCovarianceAndMean(cov_out, pose_out);
351 mrpt_msgs::GetCMGraph cm_graph_srv;
352 typedef mrpt_msgs::GetCMGraphRequest::_node_ids_type node_id_type;
353 node_id_type& matched_nodeIDs = cm_graph_srv.request.node_ids;
357 for (
typename std::vector<TNodeID>::const_iterator n_cit =
358 neighbor_nodes.begin();
359 n_cit != neighbor_nodes.end(); ++n_cit)
361 matched_nodeIDs.push_back(*n_cit);
364 MRPT_LOG_DEBUG_STREAM(
"Asking for the graph.");
368 MRPT_LOG_ERROR_STREAM(
"Service call for CM_Graph failed.");
371 MRPT_LOG_DEBUG_STREAM(
"Fetched graph successfully.");
372 MRPT_LOG_DEBUG_STREAM(cm_graph_srv.response.cm_graph);
380 MRPT_LOG_WARN_STREAM(
381 "Merging graph of \"" << neighbor->
getAgentNs() <<
"\"...");
390 cov_out = c.cov_inv.inverse();
391 graph_conn.setEdge(c);
394 graph_conn.to = *neighbor_nodes.begin();
396 graph_conn.goodness = results.goodness;
397 graph_conns.push_back(graph_conn);
400 std::map<TNodeID, TNodeID> old_to_new_mappings;
401 this->m_graph.mergeGraph(
402 other_graph, graph_conns,
403 false, &old_to_new_mappings);
408 MRPT_LOG_WARN_STREAM(
"Marking used nodes as integrated - Integrating LSs");
410 for (
typename std::vector<TNodeID>::const_iterator n_cit =
411 neighbor_nodes.begin();
412 n_cit != neighbor_nodes.end(); ++n_cit)
419 new_nodeIDs_to_scans_pairs.insert(make_pair(
420 old_to_new_mappings.at(*n_cit), nodes_params.at(*n_cit).scan));
421 MRPT_LOG_INFO_STREAM(
422 "Adding nodeID-LS of nodeID: " 423 <<
"\t[old:] " << *n_cit << endl
424 <<
"| [new:] " << old_to_new_mappings.at(*n_cit));
427 this->m_nodes_to_laser_scans2D.insert(
428 new_nodeIDs_to_scans_pairs.begin(), new_nodeIDs_to_scans_pairs.end());
436 MRPT_LOG_WARN_STREAM(
"Executing Dijkstra..." << endl);
437 this->execDijkstraNodesEstimation();
446 TNodeID last_node = *neighbor_nodes.rbegin();
448 make_pair(last_node, nodes_params.at(last_node).pose);
451 MRPT_LOG_WARN_STREAM(
452 "Nodes of neighbor [" << neighbor->
getAgentNs()
453 <<
"] have been integrated successfully");
461 template <
class GRAPH_T>
463 mrpt::obs::CActionCollection::Ptr& action,
464 mrpt::obs::CSensoryFrame::Ptr& observations,
465 mrpt::obs::CObservation::Ptr& observation,
size_t& rawlog_entry)
469 using namespace mrpt;
473 action, observations, observation, rawlog_entry);
476 bool did_register_from_map_merge;
484 "Conservative inter-graph TF computation is not yet implemented.");
489 (did_register_from_map_merge || did_register_from_batches);
493 if (this->m_enable_visuals)
495 this->updateAllVisuals();
499 return continue_exec;
503 template <
class GRAPH_T>
520 this->setLoggerName(this->m_class_name);
525 std::vector<string> nodes_up;
529 MRPT_LOG_INFO_STREAM(
530 "Waiting for master_discovery, master_sync nodes to come up....");
532 "/master_sync/get_sync_info");
533 MRPT_LOG_INFO_STREAM(
"master_discovery, master_sync are available.");
535 this->m_node_reg->setClassName(
537 this->m_edge_reg->setClassName(
539 this->m_optimizer->setClassName(
540 this->m_optimizer->getClassName() +
"_" +
580 if (this->m_enable_visuals)
583 this->m_win_manager->assignTextMessageParameters(
586 this->m_win_manager->addTextMessage(
588 mrpt::format(
"NRD: %s", this->m_node_reg->getClassName().c_str()),
593 this->m_win_manager->assignTextMessageParameters(
596 this->m_win_manager->addTextMessage(
598 mrpt::format(
"ERD: %s", this->m_edge_reg->getClassName().c_str()),
603 this->m_win_manager->assignTextMessageParameters(
606 this->m_win_manager->addTextMessage(
608 mrpt::format(
"GSO: %s", this->m_optimizer->getClassName().c_str()),
613 this->m_win_manager->assignTextMessageParameters(
616 this->m_win_manager->addTextMessage(
630 template <
class GRAPH_T>
633 const TNodeID nodeID)
const 636 using namespace mrpt::graphs::detail;
641 const TMRSlamNodeAnnotations* node_annots =
642 dynamic_cast<const TMRSlamNodeAnnotations*
>(
643 &this->m_graph.nodes.at(nodeID));
652 laser_pose = parent_t::getLSPoseForGridMapVisualization(nodeID);
664 template <
class GRAPH_T>
674 if ((*neighbors_it)->getAgentNs() == agent_ID_str)
677 neighbor = *neighbors_it;
686 template <
class GRAPH_T>
699 mrpt_msgs::GraphSlamAgents nearby_slam_agents;
710 for (GraphSlamAgents::_list_type::const_iterator it =
711 nearby_slam_agents.list.begin();
712 it != nearby_slam_agents.list.end(); ++it)
714 const GraphSlamAgent& gsa = *it;
718 return (neighbor->agent == gsa);
720 typename neighbors_t::const_iterator neighbor_it =
726 MRPT_LOG_DEBUG_STREAM(
727 "Initializing NeighborAgentProps instance for " 734 make_pair(latest_neighbor,
false));
746 template <
class GRAPH_T>
758 MRPT_LOG_DEBUG_STREAM(
"Updating list of node poses");
761 typename GRAPH_T::global_poses_t poses_to_send;
762 int poses_counter = 0;
764 NodeIDWithPoseVec ros_nodes;
767 for (
typename GRAPH_T::global_poses_t::const_reverse_iterator cit =
768 this->m_graph.nodes.rbegin();
770 cit != this->m_graph.nodes.rend());
779 NodeIDWithPose curr_node_w_pose;
781 curr_node_w_pose.node_id = cit->first;
782 curr_node_w_pose.pose = mrpt::ros1bridge::toROS_Pose(cit->second);
785 curr_node_w_pose.str_id.data = cit->second.agent_ID_str;
786 curr_node_w_pose.node_id_loc = cit->second.nodeID_loc;
788 ros_nodes.vec.push_back(curr_node_w_pose);
808 template <
class GRAPH_T>
820 if (!this->m_nodes_to_laser_scans2D.empty() &&
822 this->m_nodes_to_laser_scans2D.size())
826 *(this->m_nodes_to_laser_scans2D.rbegin());
829 if (!this->
isOwnNodeID(mrpt_last_regd_id_scan.first))
837 ASSERT_(mrpt_last_regd_id_scan.second);
840 mrpt_msgs::NodeIDWithLaserScan ros_last_regd_id_scan;
841 mrpt::ros1bridge::toROS(
842 *(mrpt_last_regd_id_scan.second), ros_last_regd_id_scan.scan);
843 ros_last_regd_id_scan.node_id = mrpt_last_regd_id_scan.first;
849 this->m_nodes_to_laser_scans2D.size();
861 template <
class GRAPH_T>
866 using namespace mrpt::graphs::detail;
869 typename GRAPH_T::global_poses_t::const_iterator global_pose_search =
870 this->m_graph.nodes.find(nodeID);
872 global_pose_search != this->m_graph.nodes.end(),
874 "isOwnNodeID called for nodeID \"%lu\" which is not " 875 "found in the graph",
876 static_cast<unsigned long>(nodeID)));
881 pose_out = &global_pose_search->second;
885 const TMRSlamNodeAnnotations* node_annots =
886 dynamic_cast<const TMRSlamNodeAnnotations*
>(
887 &global_pose_search->second);
900 template <
class GRAPH_T>
918 template <
class GRAPH_T>
926 template <
class GRAPH_T>
929 parent_t::printParams();
934 template <
class GRAPH_T>
939 template <
class GRAPH_T>
961 template <
class GRAPH_T>
975 template <
class GRAPH_T>
977 mrpt_msgs::GetCMGraph::Request& req, mrpt_msgs::GetCMGraph::Response& res)
982 set<TNodeID> nodes_set(req.node_ids.begin(), req.node_ids.end());
983 MRPT_LOG_INFO_STREAM(
984 "Called the GetCMGraph service for nodeIDs: " 985 << getSTLContainerAsString(nodes_set));
987 if (nodes_set.size() < 2)
993 GRAPH_T mrpt_subgraph;
994 this->m_graph.extractSubGraph(
995 nodes_set, &mrpt_subgraph,
1002 template <
class GRAPH_T>
1004 const TNodeID nodeID, mrpt::opengl::CSetOfObjects::Ptr& viz_object)
1010 std::string& agent_ID_str = this->m_graph.nodes.at(nodeID).agent_ID_str;
1017 obj_color = this->m_optimized_map_color;
1022 obj_color = neighbor->
color;
1024 viz_object->setColor_u8(obj_color);
1029 template <
class GRAPH_T>
1031 bool registered , std::string class_name )
1037 MRPT_LOG_ERROR_STREAM(
"m_registered_multiple_nodes = TRUE!");
1039 this->m_nodeID_max = this->m_graph.nodeCount() - 1;
1043 parent_t::monitorNodeRegistration(registered, class_name);
1049 template <
class GRAPH_T>
1051 typename GRAPH_T::global_poses_t* graph_poses)
const 1054 ASSERT_(graph_poses);
1056 for (
const auto& n : this->m_graph.nodes)
1060 graph_poses->insert(n);
1067 template <
class GRAPH_T>
1069 std::set<TNodeID>* nodes_set)
const 1074 for (
const auto& n : this->m_graph.nodes)
1078 nodes_set->insert(n.first);
1083 template <
class GRAPH_T>
1085 std::set<TNodeID>* nodes_set)
const 1093 template <
class GRAPH_T>
1096 const mrpt_msgs::GraphSlamAgent& agent_in)
1097 : engine(engine_in), agent(agent_in), has_setup_comm(false)
1106 "/" +
agent.topic_namespace.data +
"/" +
engine.m_last_regd_nodes_topic;
1108 engine.m_last_regd_id_scan_topic;
1110 "/" +
agent.topic_namespace.data +
"/" +
engine.m_cm_graph_service;
1114 "In constructor of TNeighborAgentProps for topic namespace: %s",
1115 agent.topic_namespace.data.c_str());
1119 mrpt::maps::COccupancyGridMap2D::Ptr eng_gridmap =
engine.m_gridmap_cached;
1121 eng_gridmap->getXMin(), eng_gridmap->getXMax(), eng_gridmap->getYMin(),
1122 eng_gridmap->getYMax(), eng_gridmap->getResolution());
1126 template <
class GRAPH_T>
1131 template <
class GRAPH_T>
1139 "TNeighborAgentProps: Successfully set up subscribers/services " 1140 "to agent topics for namespace [%s].",
1141 agent.topic_namespace.data.c_str());
1146 template <
class GRAPH_T>
1153 template <
class GRAPH_T>
1166 template <
class GRAPH_T>
1168 const mrpt_msgs::NodeIDWithPoseVec::ConstPtr& nodes)
1172 using namespace std;
1174 typedef typename GRAPH_T::constraint_t::type_value
pose_t;
1175 engine.logFmt(LVL_DEBUG,
"In fetchUpdatedNodesList method.");
1177 for (NodeIDWithPoseVec::_vec_type::const_iterator n_it = nodes->vec.begin();
1178 n_it != nodes->vec.end(); ++n_it)
1181 TNodeID nodeID =
static_cast<TNodeID
>(n_it->node_id);
1182 std::pair<set<TNodeID>::iterator,
bool> res =
1188 LVL_INFO,
"Just fetched a new nodeID: %lu",
1189 static_cast<unsigned long>(nodeID));
1195 curr_pose =
pose_t(mrpt::ros1bridge::fromROS(n_it->pose));
1199 poses[
static_cast<TNodeID
>(n_it->node_id)] =
pose_t(curr_pose);
1234 template <
class GRAPH_T>
1236 const mrpt_msgs::NodeIDWithLaserScan::ConstPtr& last_regd_id_scan)
1239 using namespace std;
1240 ASSERT_(last_regd_id_scan);
1241 engine.logFmt(LVL_DEBUG,
"In fetchLastRegdIDScan method.");
1246 ros_scans.push_back(*last_regd_id_scan);
1252 template <
class GRAPH_T>
1254 std::vector<TNodeID>* nodeIDs ,
1255 std::map<TNodeID, node_props_t>* nodes_params ,
1256 bool only_unused )
const 1261 using namespace std;
1265 ASSERT_(nodeIDs || nodes_params);
1268 for (std::set<TNodeID>::const_iterator n_it =
nodeIDs_set.begin();
1281 std::pair<TNodeID, node_props_t>
1285 params.first = *n_it;
1286 params.second.pose = *p;
1287 CObservation2DRangeScan::Ptr mrpt_scan =
1288 CObservation2DRangeScan::Create();
1289 const sensor_msgs::LaserScan* ros_laser_scan =
1297 if (!ros_laser_scan)
1302 mrpt::ros1bridge::fromROS(*ros_laser_scan, CPose3D(*p), *mrpt_scan);
1303 params.second.scan = mrpt_scan;
1306 nodes_params->insert(params);
1325 nodeIDs->push_back(*n_it);
1332 template <
class GRAPH_T>
1339 template <
class GRAPH_T>
1345 auto is_not_integrated = [
this](
const std::pair<TNodeID, bool> pair) {
1348 int not_integrated_num = count_if(
1352 return (not_integrated_num >= new_batch_size);
1357 template <
class GRAPH_T>
1358 const sensor_msgs::LaserScan*
1360 const TNodeID nodeID)
const 1367 for (std::vector<mrpt_msgs::NodeIDWithLaserScan>::const_iterator it =
1371 if (it->node_id == nodeID)
1382 template <
class GRAPH_T>
1384 const std::set<TNodeID>& nodeIDs,
paths_t* opt_paths)
const 1387 using namespace std;
1388 typedef std::set<TNodeID>::const_iterator set_cit;
1395 "nodeIDs is not a strict subset of the current neighbor's nodes");
1398 for (set_cit cit = nodeIDs.begin(); cit != std::prev(nodeIDs.end()); ++cit)
1400 for (set_cit cit2 = std::next(cit); cit2 != nodeIDs.end(); ++cit2)
1404 double, constraint_t::state_length,
1405 constraint_t::state_length>();
1409 opt_paths->push_back(
path_t(
1415 LVL_DEBUG,
"Filling optimal path for nodes: %lu => %lu: %s",
1416 static_cast<unsigned long>(*cit),
1417 static_cast<unsigned long>(*cit2),
1419 .curr_pose_pdf.getMeanVal()
1427 template <
class GRAPH_T>
1432 using namespace mrpt;
1434 using namespace std;
1438 std::vector<TNodeID> nodeIDs;
1439 std::map<TNodeID, node_props_t> nodes_params;
1444 for (
typename map<TNodeID, node_props_t>::const_iterator it =
1445 nodes_params.begin();
1446 it != nodes_params.end(); ++it)
1448 const CPose3D curr_pose_3d;
1449 auto obs = it->second.scan.get();
1456 template <
class GRAPH_T>
1457 const mrpt::maps::COccupancyGridMap2D::Ptr&
1470 template <
class GRAPH_T>
1472 mrpt::maps::COccupancyGridMap2D::Ptr& map)
const 1486 template <
class GRAPH_T>
1492 template <
class GRAPH_T>
1494 : conservative_find_initial_tfs_to_neighbors(false),
1495 nodes_integration_batch_size(4),
1496 num_last_regd_nodes(10),
1497 inter_group_node_count_thresh(40),
1498 inter_group_node_count_thresh_minadv(25),
1503 template <
class GRAPH_T>
1508 template <
class GRAPH_T>
1510 const CConfigFileBase& source,
const std::string& section)
1515 MRPT_LOAD_CONFIG_VAR(
1519 "Conservative behavior is not yet implemented.");
1527 "inter_group_node_count_thresh [%d]" 1528 "is set lower than the advised minimum [%d]",
1532 std::this_thread::sleep_for(std::chrono::milliseconds(2000));
1537 template <
class GRAPH_T>
1539 std::ostream& out)
const CMatrixFixed< T, ROWS, COLS > CMatrixFixedNumeric
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
mrpt::poses::CPose3D getLSPoseForGridMapVisualization(const TNodeID nodeID) const
bool pubUpdatedNodesList()
Update the last registered NodeIDs and corresponding positions of the current agent.
bool getNeighborByAgentID(const std::string &agent_ID_str, TNeighborAgentProps *&neighbor) const
Fill the TNeighborAgentProps instance based on the given agent_ID_str string that is provided...
const engine_mr_t & engine
Edge Registration Decider virtual method.
std::string m_list_neighbors_topic
Name of topic at which we publish information about the agents that we can currently communicate with...
ros::AsyncSpinner cm_graph_async_spinner
AsyncSpinner that is used to query the CM-Graph service in case a new request arrives.
ros::ServiceClient cm_graph_srvclient
void getNodeIDsOfEstimatedTrajectory(std::set< TNodeID > *nodes_set) const
const std::string & getTrimmedNs() const
Get the agent ROS namespace.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool hasNewNodesBatch(int new_batch_size)
Decide whether there are enough new nodes + scans that have not been integrated in the graph yet...
ros::Publisher m_last_regd_id_scan_pub
Publisher of the laserScan + the corresponding (last) registered node.
std::string m_sec_mr_slam_params
TColorManager m_neighbor_colors_manager
std::map< TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > nodes_to_scans2D_t
bool m_registered_multiple_nodes
Indicates whether multiple nodes were just registered. Used for checking correct node registration in...
~TNeighborAgentProps()
Destructor.
bool addNodeBatchesFromAllNeighbors()
Traverse all neighbors for which I know the inter-graph transformation, run addNodeBatchFromNeighbor...
bool call(MReq &req, MRes &res)
std::set< TNodeID > nodeIDs_set
NodeIDs that I have received from this graphSLAM agent.
ros::Subscriber last_regd_nodes_sub
ros::NodeHandle * nh
NodeHandle passed by the calling CGraphSlamEngine_MR class.
std::vector< mrpt_msgs::NodeIDWithLaserScan > ros_scans
ROS LaserScans that I have received from this graphSLAM agent.
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
std::pair< TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > MRPT_NodeIDWithLaserScan
void dumpToTextStream(std::ostream &out) const
TColor color
Unique color of current TNeighborAgentProps instance.
bool findTFsWithAllNeighbors()
Using map-merging find a potentuial transofrmation between own graph map to another agent's map and u...
constraint_t::type_value pose_t
void fillOptPaths(const std::set< TNodeID > &nodeIDs, paths_t *opt_paths) const
Fill the optimal paths for each combination of the given nodeIDs.
mrpt::graphslam::TUncertaintyPath< GRAPH_T > path_t
std::map< TNeighborAgentProps *, bool > m_neighbor_to_found_initial_tf
Map from neighbor instance to transformation from own to neighbor's graph.
void getCachedNodes(std::vector< TNodeID > *nodeIDs=NULL, std::map< TNodeID, node_props_t > *nodes_params=NULL, bool only_unused=true) const
Return cached list of nodeIDs (with their corresponding poses, LaserScans)
std::string getGridMapAlignmentResultsAsString(const mrpt::poses::CPosePDF &pdf, const mrpt::slam::CGridMapAligner::TReturnInfo &ret_info)
TNeighborAgentProps(CGraphSlamEngine_MR< GRAPH_T > &engine_in, const mrpt_msgs::GraphSlamAgent &agent_in)
Constructor.
void fetchLastRegdIDScan(const mrpt_msgs::NodeIDWithLaserScan::ConstPtr &last_regd_id_scan)
Fill the LaserScan of the last registered nodeID.
void getRobotEstimatedTrajectory(typename GRAPH_T::global_poses_t *graph_poses) const
mrpt::graphs::detail::THypothesis< GRAPH_T > hypot_t
void setupSubs()
Setup the necessary subscribers for fetching nodes, laserScans for the current neighbor.
size_t m_graph_nodes_last_size
Last known size of the m_nodes map.
mrpt::poses::CPose2D tf_self_to_neighbor_first_integrated_pose
CPose2D connecting own graph origin to neighbor first received and integrated node. If this pose is 0 then it is not yet computed.
void publish(const boost::shared_ptr< M > &message) const
const mrpt::maps::COccupancyGridMap2D::Ptr & getGridMap() const
void setCGraphSlamEnginePtr(const engine_t *engine)
std::map< TNodeID, bool > nodeID_to_is_integrated
Have I already integrated this node in my graph?
bool _execGraphSlamStep(mrpt::obs::CActionCollection::Ptr &action, mrpt::obs::CSensoryFrame::Ptr &observations, mrpt::obs::CObservation::Ptr &observation, size_t &rawlog_entry)
std::string m_sec_alignment_params
bool isOwnNodeID(const TNodeID nodeID, const global_pose_t *pose_out=NULL) const
Return true if current CGraphSlamEngine_MR object initially registered this nodeID, false otherwise.
mrpt::slam::CGridMapAligner::TConfigParams m_alignment_options
Parameters used during the alignment operation.
TOptions(const engine_mr_t &engine_in)
size_t inter_group_node_count_thresh
Lowest number of nodes that should exist in a group of nodes before evaluating it. These nodes are fetched by the other running graphSLAM agents.
virtual void setCConnectionManagerPtr(mrpt::graphslam::detail::CConnectionManager *conn_manager)
mrpt::graphslam::detail::CConnectionManager m_conn_manager
CConnectionManager instance.
void setCallbackQueue(CallbackQueueInterface *queue)
void setTColor(const TColor &color_in)
Set the color related to the current neighbor agent.
bool isEssentiallyZero(const mrpt::poses::CPose2D &p)
void fetchUpdatedNodesList(const mrpt_msgs::NodeIDWithPoseVec::ConstPtr &nodes)
Update nodeIDs + corresponding estimated poses.
const mrpt_msgs::GraphSlamAgent agent
ros::NodeHandle * m_nh
NodeHandle pointer - inherited by the parent. Redefined here for convenience.
std::pair< TNodeID, mrpt::poses::CPose2D > last_integrated_pair_neighbor_frame
Last nodeID/CPose2D of neighbor that was integrated - Pose is taken with regards to neighbor's frame ...
bool pubLastRegdIDScan()
Update the last registered NodeID and LaserScan of the current agent.
int num_last_regd_nodes
Max number of last registered NodeIDs + corresponding positions to publish.
virtual bool _execGraphSlamStep(mrpt::obs::CActionCollection::Ptr &action, mrpt::obs::CSensoryFrame::Ptr &observations, mrpt::obs::CObservation::Ptr &observation, size_t &rawlog_entry)
bool toROS(const mrpt::obs::CObservationBeaconRanges &_obj, mrpt_msgs::ObservationRangeBeacon &_msg)
void usePublishersBroadcasters()
Provide feedback about the SLAM operation.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void loadFromConfigFile(const CConfigFileBase &source, const std::string §ion)
ros::Publisher m_list_neighbors_pub
CallbackQueueInterface * getCallbackQueue() const
ros::ServiceServer m_cm_graph_srvserver
Interface for implementing deciders/optimizers related to the Condensed Measurements multi-robot grap...
mrpt::graphslam::CGraphSlamEngine_MR::TOptions m_opts
ros::CallbackQueue custom_service_queue
Custom Callback queue for processing requests for the services outside the standard CallbackQueue...
virtual void usePublishersBroadcasters()
Provide feedback about the SLAM operation.
void monitorNodeRegistration(bool registered=false, std::string class_name="Class")
Overriden method that takes in account registration of multiple nodes of other running graphSLAM agen...
bool findTFWithNeighbor(TNeighborAgentProps *neighbor)
Method is used only when I haven't found any transformation between mine and the current neighbor's g...
ros::Subscriber last_regd_id_scan_sub
CGraphSlamEngine_MR< GRAPH_T > & engine
bool conservative_find_initial_tfs_to_neighbors
Be conservative when it comes to deciding the initial transformation of own graph with regards to gra...
std::string m_mr_ns
Condensed Measurements topic namespace.
int nodes_integration_batch_size
After an inter-graph transformation is found between own graph and a neighbor's map, newly fetched neighbor's nodes are added in batches.
mrpt::maps::COccupancyGridMap2D::Ptr gridmap_cached
Pointer to the gridmap object of the neighbor.
ros::Publisher m_last_regd_nodes_pub
Publisher of the last registered nodeIDs and positions.
GRAPH_T::global_pose_t global_pose_t
bool getCMGraph(mrpt_msgs::GetCMGraph::Request &req, mrpt_msgs::GetCMGraph::Response &res)
Compute and fill the Condensed Measurements Graph.
const sensor_msgs::LaserScan * getLaserScanByNodeID(const TNodeID nodeID) const
void setObjectPropsFromNodeID(const TNodeID nodeID, mrpt::opengl::CSetOfObjects::Ptr &viz_object)
std::string getAgentNs() const
std::vector< hypot_t > hypots_t
void computeGridMap() const
Using the fetched LaserScans and nodeID positions, compute the occupancy gridmap of the given neighbo...
void setupSrvs()
Setup necessary services for neighbor.
void getNearbySlamAgents(mrpt_msgs::GraphSlamAgents *agents_vec, bool ignore_self=true)
Fill the given vector with the SLAM Agents that the current manager can see and communicate with...
bool fromROS(const marker_msgs::MarkerDetection &_msg, const mrpt::poses::CPose3D &sensorPoseOnRobot, mrpt::obs::CObservationBearingRange &_obj)
virtual void addBatchOfNodeIDsAndScans(const std::map< TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > &nodeIDs_to_scans2D)
neighbors_t m_neighbors
GraphSlamAgent instance pointer to TNeighborAgentProps.
std::string last_regd_nodes_topic
size_t inter_group_node_count_thresh_minadv
Minimum advised limit of inter_group_node_count_thresh.
double m_offset_y_nrd
Display the Deciders/Optimizers with which we are running as well as the namespace of the current age...
void setupComm()
Wrapper for calling setupSubs, setupSrvs.
void getAllOwnNodes(std::set< TNodeID > *nodes_set) const
Fill given set with the nodeIDs that were initially registered by the current graphSLAM engine (and n...
std::string last_regd_id_scan_topic
GRAPH_T::global_poses_t poses
Poses that I have received from this graphSLAM agent.
std::string m_cm_graph_service
Name of the server which is to be called when other agent wants to have a subgraph of certain nodes r...
std::string cm_graph_service
ROSCPP_DECL bool getNodes(V_string &nodes)
mrpt::graphslam::CGraphSlamEngine derived class for executing multi-robot graphSLAM ...
std::string m_last_regd_id_scan_topic
Name of the topic that the last registered laser scan (+ corresponding nodeID) is published at...
std::vector< path_t > paths_t
double m_offset_y_namespace
GRAPH_T::constraint_t constraint_t
ROSCPP_DECL bool search(const std::string &ns, const std::string &key, std::string &result)
size_t m_nodes_to_laser_scans2D_last_size
Last known size of the m_nodes_to_laser_scans2D map.
Struct responsible for holding properties (nodeIDs, node positions, LaserScans) that have been regist...
void readROSParameters()
Read configuration parameters from the ROS parameter server.
bool addNodeBatchFromNeighbor(TNeighborAgentProps *neighbor)
neighbors for which I know the inter-graph transformation, add new batches of fetches nodeIDs and sca...
std::string m_last_regd_nodes_topic
Name of the topic that the last X registered nodes + positions are going to be published at...
void setupComm()
Wrapper method around the protected setup* class methods.
bool hasNewData() const
Return True if there are new data (node positions and corresponding LaserScans available) ...
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)
int m_text_index_namespace