14 #include <mrpt/version.h> 16 #if MRPT_VERSION>=0x199 17 #include <mrpt/math/CMatrixFixed.h> 20 template <
typename T, std::
size_t ROWS, std::
size_t COLS>
21 using CMatrixFixedNumeric = CMatrixFixed<T,ROWS,COLS>;
26 namespace mrpt {
namespace graphslam {
28 template<
class GRAPH_T>
31 const std::string& config_file,
32 const std::string& rawlog_fname,
33 const std::string& fname_GT ,
34 mrpt::graphslam::CWindowManager* win_manager ,
35 mrpt::graphslam::deciders::CNodeRegistrationDecider<GRAPH_T>* node_reg ,
36 mrpt::graphslam::deciders::CEdgeRegistrationDecider<GRAPH_T>* edge_reg ,
37 mrpt::graphslam::optimizers::CGraphSlamOptimizer<GRAPH_T>* optimizer ):
48 dynamic_cast<
mrpt::utils::COutputLogger*>(this), nh),
50 m_graph_nodes_last_size(0),
51 m_registered_multiple_nodes(false),
52 cm_graph_async_spinner( 1, &this->custom_service_queue),
53 m_sec_alignment_params(
"AlignmentParameters"),
54 m_sec_mr_slam_params(
"MultiRobotParameters"),
60 template<
class GRAPH_T>
62 MRPT_LOG_DEBUG_STREAM(
63 "In Destructor: Deleting CGraphSlamEngine_MR instance...");
66 for (
typename neighbors_t::iterator
75 template<
class GRAPH_T>
83 neighbor->tf_self_to_neighbor_first_integrated_pose) &&
84 neighbor->hasNewData() &&
87 if (loc_ret_val) { ret_val =
true; }
95 template<
class GRAPH_T>
106 std::vector<TNodeID> nodeIDs;
107 std::map<TNodeID, node_props_t> nodes_params;
113 mrpt_msgs::GetCMGraph cm_graph_srv;
116 for (
const auto n : nodeIDs) {
117 cm_graph_srv.request.nodeIDs.push_back(n);
120 MRPT_LOG_DEBUG_STREAM(
"Asking for the graph.");
123 MRPT_LOG_ERROR_STREAM(
"Service call for CM_Graph failed.");
126 MRPT_LOG_DEBUG_STREAM(
"Fetched graph successfully.");
127 MRPT_LOG_DEBUG_STREAM(cm_graph_srv.response.cm_graph);
130 mrpt_bridge::convert(cm_graph_srv.response.cm_graph, other_graph);
135 MRPT_LOG_WARN_STREAM(
"Merging new batch from \"" << neighbor->
getAgentNs() <<
"\"..." << endl
136 <<
"Batch: " << getSTLContainerAsString(cm_graph_srv.request.nodeIDs));
141 pair<TNodeID, node_props_t> node_props_to_connect = *nodes_params.begin();
145 c.mean = node_props_to_connect.second.pose -
147 #if MRPT_VERSION>=0x199 148 c.cov_inv.setIdentity();
152 graph_conn.setEdge(c);
154 graph_conn.from = INVALID_NODEID;
157 for (
const auto n : this->m_graph.nodes) {
158 if (n.second.agent_ID_str == neighbor->
getAgentNs() &&
160 graph_conn.from = n.first;
164 ASSERT_(graph_conn.from != INVALID_NODEID);
165 graph_conn.to = node_props_to_connect.first;
167 MRPT_LOG_DEBUG_STREAM(
"Hypothesis for adding the batch of nodes: " << graph_conn);
168 graph_conns.push_back(graph_conn);
171 std::map<TNodeID, TNodeID> old_to_new_mappings;
172 this->m_graph.mergeGraph(
173 other_graph, graph_conns,
175 &old_to_new_mappings);
180 MRPT_LOG_WARN_STREAM(
"Marking used nodes as integrated - Integrating LSs");
182 for (
typename std::vector<TNodeID>::const_iterator
183 n_cit = nodeIDs.begin();
184 n_cit != nodeIDs.end();
192 new_nodeIDs_to_scans_pairs.insert(make_pair(
193 old_to_new_mappings.at(*n_cit),
194 nodes_params.at(*n_cit).scan));
195 MRPT_LOG_INFO_STREAM(
"Adding nodeID-LS of nodeID: " 196 <<
"\t[old:] " << *n_cit << endl
197 <<
"| [new:] " << old_to_new_mappings.at(*n_cit));
200 this->m_nodes_to_laser_scans2D.insert(
201 new_nodeIDs_to_scans_pairs.begin(),
202 new_nodeIDs_to_scans_pairs.end());
207 this->execDijkstraNodesEstimation();
212 TNodeID last_node = *nodeIDs.rbegin();
215 nodes_params.at(last_node).pose);
222 template<
class GRAPH_T>
237 bool ret_val =
false;
240 for (
typename neighbors_t::iterator
251 MRPT_LOG_DEBUG_STREAM(
252 "Updating own cached map after successful node registration...");
268 template<
class GRAPH_T>
279 bool ret_val =
false;
281 std::vector<TNodeID> neighbor_nodes;
282 std::map<TNodeID, node_props_t> nodes_params;
292 COccupancyGridMap2D::Ptr neighbor_gridmap = neighbor->
getGridMap();
293 CGridMapAligner gridmap_aligner;
296 CGridMapAligner::TReturnInfo results;
299 CPosePDFGaussian init_estim;
301 this->logFmt(LVL_INFO,
302 "Trying to align the maps, initial estimation: %s",
303 init_estim.mean.asString().c_str());
309 const CPosePDF::Ptr pdf_tmp = gridmap_aligner.AlignPDF(
310 this->m_gridmap_cached.get(), neighbor_gridmap.get(),
312 &run_time, &results);
313 this->logFmt(LVL_INFO,
"Elapsed Time: %f", run_time);
314 CPosePDFSOG::Ptr pdf_out = CPosePDFSOG::Create();
315 pdf_out->copyFrom(*pdf_tmp);
317 CPose2D pose_out; CMatrixDouble33 cov_out;
318 pdf_out->getMostLikelyCovarianceAndMean(cov_out, pose_out);
320 this->logFmt(LVL_INFO,
"%s\n",
324 if (results.goodness > 0.999 ||
337 mrpt_msgs::GetCMGraph cm_graph_srv;
338 typedef mrpt_msgs::GetCMGraphRequest::_nodeIDs_type nodeID_type;
339 nodeID_type& matched_nodeIDs =
340 cm_graph_srv.request.nodeIDs;
344 for (
typename std::vector<TNodeID>::const_iterator
345 n_cit = neighbor_nodes.begin();
346 n_cit != neighbor_nodes.end();
348 matched_nodeIDs.push_back(*n_cit);
351 MRPT_LOG_DEBUG_STREAM(
"Asking for the graph.");
354 MRPT_LOG_ERROR_STREAM(
"Service call for CM_Graph failed.");
357 MRPT_LOG_DEBUG_STREAM(
"Fetched graph successfully.");
358 MRPT_LOG_DEBUG_STREAM(cm_graph_srv.response.cm_graph);
361 mrpt_bridge::convert(cm_graph_srv.response.cm_graph, other_graph);
366 MRPT_LOG_WARN_STREAM(
"Merging graph of \"" << neighbor->
getAgentNs() <<
"\"...");
375 #if MRPT_VERSION>=0x199 376 cov_out = c.cov_inv.inverse();
378 cov_out.inv(c.cov_inv);
380 graph_conn.setEdge(c);
383 graph_conn.to = *neighbor_nodes.begin();
385 graph_conn.goodness = results.goodness;
386 graph_conns.push_back(graph_conn);
389 std::map<TNodeID, TNodeID> old_to_new_mappings;
390 this->m_graph.mergeGraph(
391 other_graph, graph_conns,
393 &old_to_new_mappings);
398 MRPT_LOG_WARN_STREAM(
"Marking used nodes as integrated - Integrating LSs");
400 for (
typename std::vector<TNodeID>::const_iterator
401 n_cit = neighbor_nodes.begin();
402 n_cit != neighbor_nodes.end();
410 new_nodeIDs_to_scans_pairs.insert(make_pair(
411 old_to_new_mappings.at(*n_cit),
412 nodes_params.at(*n_cit).scan));
413 MRPT_LOG_INFO_STREAM(
"Adding nodeID-LS of nodeID: " 414 <<
"\t[old:] " << *n_cit << endl
415 <<
"| [new:] " << old_to_new_mappings.at(*n_cit));
418 this->m_nodes_to_laser_scans2D.insert(
419 new_nodeIDs_to_scans_pairs.begin(),
420 new_nodeIDs_to_scans_pairs.end());
429 MRPT_LOG_WARN_STREAM(
"Executing Dijkstra..." << endl);
430 this->execDijkstraNodesEstimation();
439 TNodeID last_node = *neighbor_nodes.rbegin();
442 nodes_params.at(last_node).pose);
445 MRPT_LOG_WARN_STREAM(
"Nodes of neighbor [" << neighbor->
getAgentNs()
446 <<
"] have been integrated successfully");
454 template<
class GRAPH_T>
456 mrpt::obs::CActionCollection::Ptr& action,
457 mrpt::obs::CSensoryFrame::Ptr& observations,
458 mrpt::obs::CObservation::Ptr& observation,
459 size_t& rawlog_entry) {
462 using namespace mrpt;
466 action, observations, observation, rawlog_entry);
469 bool did_register_from_map_merge;
474 THROW_EXCEPTION(
"Conservative inter-graph TF computation is not yet implemented.");
481 if (this->m_enable_visuals) {
482 this->updateAllVisuals();
486 return continue_exec;
490 template<
class GRAPH_T>
507 this->setLoggerName(this->m_class_name);
512 std::vector<string> nodes_up;
516 MRPT_LOG_INFO_STREAM(
"Waiting for master_discovery, master_sync nodes to come up....");
518 MRPT_LOG_INFO_STREAM(
"master_discovery, master_sync are available.");
520 this->m_node_reg->setClassName(
522 this->m_edge_reg->setClassName(
524 this->m_optimizer->setClassName(
558 if (this->m_enable_visuals) {
560 this->m_win_manager->assignTextMessageParameters(
563 this->m_win_manager->addTextMessage(this->m_offset_x_left, -
m_offset_y_nrd,
564 mrpt::format(
"NRD: %s", this->m_node_reg->getClassName().c_str()),
569 this->m_win_manager->assignTextMessageParameters(
572 this->m_win_manager->addTextMessage(
574 mrpt::format(
"ERD: %s", this->m_edge_reg->getClassName().c_str()),
579 this->m_win_manager->assignTextMessageParameters(
582 this->m_win_manager->addTextMessage(
584 mrpt::format(
"GSO: %s", this->m_optimizer->getClassName().c_str()),
589 this->m_win_manager->assignTextMessageParameters(
592 this->m_win_manager->addTextMessage(
607 template<
class GRAPH_T>
610 const TNodeID nodeID)
const {
612 using namespace mrpt::graphs::detail;
617 const TMRSlamNodeAnnotations* node_annots =
dynamic_cast<const TMRSlamNodeAnnotations*
>(
618 &this->m_graph.nodes.at(nodeID));
626 laser_pose = parent_t::getLSPoseForGridMapVisualization(nodeID);
636 template<
class GRAPH_T>
647 if ((*neighbors_it)->getAgentNs() == agent_ID_str) {
649 neighbor = *neighbors_it;
658 template<
class GRAPH_T>
671 mrpt_msgs::GraphSlamAgents nearby_slam_agents;
682 for (GraphSlamAgents::_list_type::const_iterator
683 it = nearby_slam_agents.list.begin();
684 it != nearby_slam_agents.list.end();
687 const GraphSlamAgent& gsa = *it;
691 return (neighbor->agent == gsa);
693 typename neighbors_t::const_iterator neighbor_it = find_if(
699 MRPT_LOG_DEBUG_STREAM(
"Initializing NeighborAgentProps instance for " 705 latest_neighbor,
false));
717 template<
class GRAPH_T>
727 MRPT_LOG_DEBUG_STREAM(
"Updating list of node poses");
730 typename GRAPH_T::global_poses_t poses_to_send;
731 int poses_counter = 0;
733 NodeIDWithPose_vec ros_nodes;
736 for (
typename GRAPH_T::global_poses_t::const_reverse_iterator
737 cit = this->m_graph.nodes.rbegin();
739 cit != this->m_graph.nodes.rend());
747 NodeIDWithPose curr_node_w_pose;
749 curr_node_w_pose.nodeID = cit->first;
750 mrpt_bridge::convert(cit->second, curr_node_w_pose.pose);
753 curr_node_w_pose.str_ID.data = cit->second.agent_ID_str;
754 curr_node_w_pose.nodeID_loc = cit->second.nodeID_loc;
756 ros_nodes.vec.push_back(curr_node_w_pose);
775 template<
class GRAPH_T>
787 if (!this->m_nodes_to_laser_scans2D.empty() &&
791 *(this->m_nodes_to_laser_scans2D.rbegin());
795 if (!this->
isOwnNodeID(mrpt_last_regd_id_scan.first)) {
802 ASSERT_(mrpt_last_regd_id_scan.second);
805 mrpt_msgs::NodeIDWithLaserScan ros_last_regd_id_scan;
806 convert(*(mrpt_last_regd_id_scan.second), ros_last_regd_id_scan.scan);
807 ros_last_regd_id_scan.nodeID = mrpt_last_regd_id_scan.first;
813 this->m_nodes_to_laser_scans2D.size();
826 template<
class GRAPH_T>
828 const TNodeID nodeID,
831 using namespace mrpt::graphs::detail;
834 typename GRAPH_T::global_poses_t::const_iterator global_pose_search =
835 this->m_graph.nodes.find(nodeID);
836 ASSERTMSG_(global_pose_search != this->m_graph.nodes.end(),
838 "isOwnNodeID called for nodeID \"%lu\" which is not found in the graph",
839 static_cast<unsigned long>(nodeID)));
843 pose_out = &global_pose_search->second;
847 const TMRSlamNodeAnnotations* node_annots =
dynamic_cast<const TMRSlamNodeAnnotations*
>(
848 &global_pose_search->second);
859 template<
class GRAPH_T>
876 template<
class GRAPH_T>
884 template<
class GRAPH_T>
886 parent_t::printParams();
893 template<
class GRAPH_T>
896 template<
class GRAPH_T>
923 template<
class GRAPH_T>
936 template<
class GRAPH_T>
938 mrpt_msgs::GetCMGraph::Request& req,
939 mrpt_msgs::GetCMGraph::Response& res) {
944 set<TNodeID> nodes_set(req.nodeIDs.begin(), req.nodeIDs.end());
945 MRPT_LOG_INFO_STREAM(
"Called the GetCMGraph service for nodeIDs: " 946 << getSTLContainerAsString(nodes_set));
948 if (nodes_set.size() < 2) {
return false; }
951 GRAPH_T mrpt_subgraph;
952 this->m_graph.extractSubGraph(nodes_set, &mrpt_subgraph,
955 mrpt_bridge::convert(mrpt_subgraph, res.cm_graph);
959 template<
class GRAPH_T>
961 const TNodeID nodeID,
962 mrpt::opengl::CSetOfObjects::Ptr& viz_object) {
968 std::string& agent_ID_str = this->m_graph.nodes.at(nodeID).agent_ID_str;
974 obj_color = this->m_optimized_map_color;
978 obj_color = neighbor->
color;
980 viz_object->setColor_u8(obj_color);
986 template<
class GRAPH_T>
989 std::string class_name) {
994 MRPT_LOG_ERROR_STREAM(
"m_registered_multiple_nodes = TRUE!");
996 this->m_nodeID_max = this->m_graph.nodeCount()-1;
999 parent_t::monitorNodeRegistration(registered, class_name);
1005 template<
class GRAPH_T>
1007 typename GRAPH_T::global_poses_t* graph_poses)
const {
1009 ASSERT_(graph_poses);
1011 for (
const auto& n : this->m_graph.nodes) {
1013 graph_poses->insert(n);
1020 template<
class GRAPH_T>
1026 for (
const auto& n : this->m_graph.nodes) {
1028 nodes_set->insert(n.first);
1033 template<
class GRAPH_T>
1036 std::set<TNodeID>* nodes_set)
const {
1043 template<
class GRAPH_T>
1046 const mrpt_msgs::GraphSlamAgent& agent_in):
1049 has_setup_comm(false)
1060 engine.m_last_regd_nodes_topic;
1062 engine.m_last_regd_id_scan_topic;
1064 engine.m_cm_graph_service;
1067 "In constructor of TNeighborAgentProps for topic namespace: %s",
1068 agent.topic_namespace.data.c_str());
1072 COccupancyGridMap2D::Ptr eng_gridmap =
engine.m_gridmap_cached;
1074 eng_gridmap->getXMin(),
1075 eng_gridmap->getXMax(),
1076 eng_gridmap->getYMin(),
1077 eng_gridmap->getYMax(),
1078 eng_gridmap->getResolution());
1082 template<
class GRAPH_T>
1085 template<
class GRAPH_T>
1094 "TNeighborAgentProps: Successfully set up subscribers/services " 1095 "to agent topics for namespace [%s].",
1096 agent.topic_namespace.data.c_str());
1101 template<
class GRAPH_T>
1109 template<
class GRAPH_T>
1124 template<
class GRAPH_T>
1127 const mrpt_msgs::NodeIDWithPose_vec::ConstPtr& nodes) {
1131 using namespace std;
1134 typedef typename GRAPH_T::constraint_t::type_value
pose_t;
1135 engine.logFmt(LVL_DEBUG,
"In fetchUpdatedNodesList method.");
1137 for (NodeIDWithPose_vec::_vec_type::const_iterator
1138 n_it = nodes->vec.begin();
1139 n_it != nodes->vec.end();
1143 TNodeID nodeID =
static_cast<TNodeID
>(n_it->nodeID);
1144 std::pair<set<TNodeID>::iterator,
bool> res =
1148 engine.logFmt(LVL_INFO,
"Just fetched a new nodeID: %lu",
1149 static_cast<unsigned long>(nodeID));
1157 poses[
static_cast<TNodeID
>(n_it->nodeID)] =
1158 convert(n_it->pose, curr_pose);
1191 template<
class GRAPH_T>
1194 const mrpt_msgs::NodeIDWithLaserScan::ConstPtr& last_regd_id_scan) {
1196 using namespace std;
1198 ASSERT_(last_regd_id_scan);
1199 engine.logFmt(LVL_DEBUG,
"In fetchLastRegdIDScan method.");
1204 ros_scans.push_back(*last_regd_id_scan);
1210 template<
class GRAPH_T>
1212 std::vector<TNodeID>* nodeIDs,
1216 bool only_unused)
const {
1221 using namespace std;
1225 ASSERT_(nodeIDs || nodes_params);
1228 for (std::set<TNodeID>::const_iterator
1239 std::pair<TNodeID, node_props_t> params;
1242 params.first = *n_it;
1243 params.second.pose = *p;
1244 CObservation2DRangeScan::Ptr mrpt_scan = CObservation2DRangeScan::Create();
1245 const sensor_msgs::LaserScan* ros_laser_scan =
1253 if (!ros_laser_scan) {
continue; }
1255 mrpt_bridge::convert(*ros_laser_scan, CPose3D(*p), *mrpt_scan);
1256 params.second.scan = mrpt_scan;
1259 nodes_params->insert(params);
1276 nodeIDs->push_back(*n_it);
1283 template<
class GRAPH_T>
1290 template<
class GRAPH_T>
1295 auto is_not_integrated = [
this](
const std::pair<TNodeID, bool> pair) {
1298 int not_integrated_num = count_if(
1303 return (not_integrated_num >= new_batch_size);
1309 template<
class GRAPH_T>
1310 const sensor_msgs::LaserScan*
1313 const TNodeID nodeID)
const {
1319 for (std::vector<mrpt_msgs::NodeIDWithLaserScan>::const_iterator
1323 if (it->nodeID == nodeID) {
1333 template<
class GRAPH_T>
1336 const std::set<TNodeID>& nodeIDs,
1339 using namespace std;
1341 typedef std::set<TNodeID>::const_iterator set_cit;
1345 nodeIDs.begin(), nodeIDs.end()),
1346 "nodeIDs is not a strict subset of the current neighbor's nodes");
1349 for (set_cit cit = nodeIDs.begin();
1350 cit != std::prev(nodeIDs.end());
1353 for (set_cit cit2 = std::next(cit);
1354 cit2 != nodeIDs.end();
1360 mrpt::math::CMatrixFixedNumeric<double,
1361 constraint_t::state_length,
1362 constraint_t::state_length>();
1366 opt_paths->push_back(
path_t(
1372 "Filling optimal path for nodes: %lu => %lu: %s",
1373 static_cast<unsigned long>(*cit),
1374 static_cast<unsigned long>(*cit2),
1375 opt_paths->back().curr_pose_pdf.getMeanVal().asString().c_str());
1382 template<
class GRAPH_T>
1388 using namespace mrpt;
1390 using namespace std;
1394 std::vector<TNodeID> nodeIDs;
1395 std::map<TNodeID, node_props_t> nodes_params;
1400 for (
typename map<TNodeID, node_props_t>::const_iterator
1401 it = nodes_params.begin();
1402 it != nodes_params.end();
1404 const CPose3D curr_pose_3d;
1405 gridmap_cached->insertObservation(it->second.scan.get(), &curr_pose_3d);
1411 template<
class GRAPH_T>
1412 const mrpt::maps::COccupancyGridMap2D::Ptr&
1424 template<
class GRAPH_T>
1439 template<
class GRAPH_T>
1444 template<
class GRAPH_T>
1446 conservative_find_initial_tfs_to_neighbors(false),
1447 nodes_integration_batch_size(4),
1448 num_last_regd_nodes(10),
1449 inter_group_node_count_thresh(40),
1450 inter_group_node_count_thresh_minadv(25),
1455 template<
class GRAPH_T>
1459 template<
class GRAPH_T>
1461 const CConfigFileBase& source,
1462 const std::string& section) {
1469 "Conservative behavior is not yet implemented.");
1476 "inter_group_node_count_thresh [%d]" 1477 "is set lower than the advised minimum [%d]",
1481 std::this_thread::sleep_for(std::chrono::milliseconds(2000));
1487 template<
class GRAPH_T>
1489 #
if MRPT_VERSION>=0x199
1490 std::ostream& out)
const {
1492 mrpt::utils::CStream& out)
const {
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void dumpToTextStream(mrpt::utils::CStream &out) const
bool pubUpdatedNodesList()
Update the last registered NodeIDs and corresponding positions of the current agent.
void computeGridMap() const
Using the fetched LaserScans and nodeID positions, compute the occupancy gridmap of the given neighbo...
const engine_mr_t & engine
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)
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.
void publish(const boost::shared_ptr< M > &message) const
ros::ServiceClient cm_graph_srvclient
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
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
TColor color
Unique color of current TNeighborAgentProps instance.
void getNodeIDsOfEstimatedTrajectory(std::set< TNodeID > *nodes_set) const
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
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.
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...
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.
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.
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
mrpt::slam::CGridMapAligner::TConfigParams m_alignment_options
Parameters used during the alignment operation.
TOptions(const engine_mr_t &engine_in)
void fillOptPaths(const std::set< TNodeID > &nodeIDs, paths_t *opt_paths) const
Fill the optimal paths for each combination of the given nodeIDs.
void getRobotEstimatedTrajectory(typename GRAPH_T::global_poses_t *graph_poses) const
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)
const mrpt_msgs::GraphSlamAgent agent
ros::NodeHandle * m_nh
NodeHandle pointer - inherited by the parent. Redefined here for convenience.
bool pubLastRegdIDScan()
Update the last registered NodeID and LaserScan of the current agent.
void fetchUpdatedNodesList(const mrpt_msgs::NodeIDWithPose_vec::ConstPtr &nodes)
Update nodeIDs + corresponding estimated poses.
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)
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
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...
mrpt::graphslam::detail::TNodeProps< GRAPH_T > node_props_t
virtual void usePublishersBroadcasters()
Provide feedback about the SLAM operation.
mrpt::poses::CPose3D getLSPoseForGridMapVisualization(const TNodeID nodeID) const
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...
std::map< TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > nodes_to_scans2D_t
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.
const std::string & getTrimmedNs() const
Get the agent ROS 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.
void setObjectPropsFromNodeID(const TNodeID nodeID, mrpt::opengl::CSetOfObjects::Ptr &viz_object)
std::vector< hypot_t > hypots_t
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...
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.
std::string last_regd_id_scan_topic
GRAPH_T::global_poses_t poses
Poses that I have received from this graphSLAM agent.
void convert(const A &a, B &b)
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
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.
ROSCPP_DECL bool getNodes(V_string &nodes)
CallbackQueueInterface * getCallbackQueue() const
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 ...
mrpt::graphslam::CGraphSlamEngine derived class for executing multi-robot graphSLAM ...
bool hasNewData() const
Return True if there are new data (node positions and corresponding LaserScans available) ...
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...
std::string getAgentNs() const
void setupComm()
Wrapper method around the protected setup* class methods.
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)
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...
const sensor_msgs::LaserScan * getLaserScanByNodeID(const TNodeID nodeID) const
int m_text_index_namespace