Go to the documentation of this file.
20 #include <mrpt_msgs/NodeIDWithPoseVec.h>
21 #include <mrpt_msgs/NodeIDWithLaserScan.h>
22 #include <mrpt_msgs/NetworkOfPoses.h>
23 #include <mrpt_msgs/GetCMGraph.h>
25 #include <mrpt/ros1bridge/laser_scan.h>
26 #include <sensor_msgs/LaserScan.h>
27 #include <std_msgs/String.h>
28 #include <mrpt/poses/CPosePDFGaussian.h>
29 #include <mrpt/poses/CPosePDFSOG.h>
30 #include <mrpt/math/utils.h>
31 #include <mrpt/system/os.h>
32 #include <mrpt/slam/CGridMapAligner.h>
33 #include <mrpt/graphs/TMRSlamNodeAnnotations.h>
34 #include <mrpt/graphslam/misc/TUncertaintyPath.h>
35 #include <mrpt/graphslam/misc/TNodeProps.h>
36 #include <mrpt/img/TColorManager.h>
37 #include <mrpt/img/TColor.h>
38 #include <mrpt/graphs/TNodeID.h>
39 #include <mrpt/config/CConfigFileBase.h>
40 #include <mrpt/system/COutputLogger.h>
41 #include <mrpt/containers/stl_containers_utils.h>
47 using namespace mrpt::img;
48 using namespace mrpt::graphs;
49 using namespace mrpt::config;
50 using namespace mrpt::system;
51 using namespace mrpt::containers;
60 template <
class GRAPH_T>
67 typedef typename constraint_t::type_value
pose_t;
68 typedef std::pair<TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr>
70 typedef std::map<TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr>
73 typedef typename mrpt::graphs::detail::THypothesis<GRAPH_T>
hypot_t;
77 typedef typename mrpt::graphslam::detail::TNodeProps<GRAPH_T>
node_props_t;
78 typedef mrpt::graphslam::TUncertaintyPath<GRAPH_T>
path_t;
85 const std::string& rawlog_fname =
"",
const std::string& fname_GT =
"",
86 mrpt::graphslam::CWindowManager* win_manager = NULL,
87 mrpt::graphslam::deciders::CNodeRegistrationDecider<GRAPH_T>* node_reg =
89 mrpt::graphslam::deciders::CEdgeRegistrationDecider<GRAPH_T>* edge_reg =
91 mrpt::graphslam::optimizers::CGraphSlamOptimizer<GRAPH_T>* optimizer =
96 bool _execGraphSlamStep(
97 mrpt::obs::CActionCollection::Ptr& action,
98 mrpt::obs::CSensoryFrame::Ptr& observations,
99 mrpt::obs::CObservation::Ptr& observation,
size_t& rawlog_entry);
112 const mrpt_msgs::GraphSlamAgent& agent_in);
131 void fetchUpdatedNodesList(
132 const mrpt_msgs::NodeIDWithPoseVec::ConstPtr& nodes);
135 void fetchLastRegdIDScan(
136 const mrpt_msgs::NodeIDWithLaserScan::ConstPtr& last_regd_id_scan);
154 std::vector<TNodeID>* nodeIDs = NULL,
155 std::map<TNodeID, node_props_t>* nodes_params = NULL,
156 bool only_unused =
true)
const;
161 const std::set<TNodeID>& nodeIDs,
paths_t* opt_paths)
const;
165 void computeGridMap()
const;
166 const mrpt::maps::COccupancyGridMap2D::Ptr& getGridMap()
const;
170 void getGridMap(mrpt::maps::COccupancyGridMap2D::Ptr& map)
const;
178 bool hasNewData()
const;
181 return this->agent.topic_namespace.data;
183 void resetFlags()
const;
186 return (this->agent == other.
agent);
190 return (this->agent < other.
agent);
195 const sensor_msgs::LaserScan* getLaserScanByNodeID(
196 const TNodeID nodeID)
const;
204 const mrpt_msgs::GraphSlamAgent
agent;
213 bool hasNewNodesBatch(
int new_batch_size);
219 void setTColor(
const TColor& color_in) { color = color_in; }
229 typename GRAPH_T::global_poses_t
poses;
279 std::pair<TNodeID, mrpt::poses::CPose2D>
295 const TNodeID nodeID,
const global_pose_t* pose_out = NULL)
const;
301 bool addNodeBatchesFromAllNeighbors();
312 bool addNodeBatchFromNeighbor(TNeighborAgentProps* neighbor);
322 bool findTFsWithAllNeighbors();
331 bool findTFWithNeighbor(TNeighborAgentProps* neighbor);
338 bool getNeighborByAgentID(
339 const std::string& agent_ID_str, TNeighborAgentProps*& neighbor)
const;
351 bool pubUpdatedNodesList();
361 bool pubLastRegdIDScan();
363 void usePublishersBroadcasters();
372 mrpt_msgs::GetCMGraph::Request& req,
373 mrpt_msgs::GetCMGraph::Response& res);
376 void readROSParameters();
377 void printParams()
const;
378 mrpt::poses::CPose3D getLSPoseForGridMapVisualization(
379 const TNodeID nodeID)
const;
380 void setObjectPropsFromNodeID(
381 const TNodeID nodeID, mrpt::opengl::CSetOfObjects::Ptr& viz_object);
386 void monitorNodeRegistration(
387 bool registered =
false, std::string class_name =
"Class");
391 void getAllOwnNodes(std::set<TNodeID>* nodes_set)
const;
392 void getNodeIDsOfEstimatedTrajectory(std::set<TNodeID>* nodes_set)
const;
393 void getRobotEstimatedTrajectory(
394 typename GRAPH_T::global_poses_t* graph_poses)
const;
514 void loadFromConfigFile(
515 const CConfigFileBase& source,
const std::string& section);
516 void dumpToTextStream(std::ostream& out)
const;
double m_offset_y_nrd
Display the Deciders/Optimizers with which we are running as well as the namespace of the current age...
mrpt::slam::CGridMapAligner::TConfigParams m_alignment_options
Parameters used during the alignment operation.
int m_text_index_namespace
TColorManager m_neighbor_colors_manager
std::string m_sec_mr_slam_params
bool operator==(const TNeighborAgentProps &other) const
ros::Subscriber last_regd_nodes_sub
size_t inter_group_node_count_thresh
Lowest number of nodes that should exist in a group of nodes before evaluating it....
std::string m_last_regd_id_scan_topic
Name of the topic that the last registered laser scan (+ corresponding nodeID) is published at.
TColor color
Unique color of current TNeighborAgentProps instance.
std::set< TNodeID > nodeIDs_set
NodeIDs that I have received from this graphSLAM agent.
std::vector< hypot_t > hypots_t
CGraphSlamEngine_MR< GRAPH_T > self_t
ros::ServiceClient cm_graph_srvclient
int nodes_integration_batch_size
After an inter-graph transformation is found between own graph and a neighbor's map,...
ros::NodeHandle * nh
NodeHandle passed by the calling CGraphSlamEngine_MR class.
mrpt::graphslam::detail::TNodeProps< GRAPH_T > node_props_t
ros::NodeHandle * m_nh
NodeHandle pointer - inherited by the parent. Redefined here for convenience.
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::vector< hypot_t * > hypotsp_t
ros::Publisher m_last_regd_id_scan_pub
Publisher of the laserScan + the corresponding (last) registered node.
std::vector< mrpt_msgs::NodeIDWithLaserScan > ros_scans
ROS LaserScans that I have received from this graphSLAM agent.
std::vector< TNeighborAgentProps * > neighbors_t
size_t inter_group_node_count_thresh_minadv
Minimum advised limit of inter_group_node_count_thresh.
bool operator<(const TNeighborAgentProps &other) const
void setTColor(const TColor &color_in)
Set the color related to the current neighbor agent.
std::string m_mr_ns
Condensed Measurements topic namespace.
mrpt::graphslam::TUncertaintyPath< GRAPH_T > path_t
const engine_mr_t & engine
const mrpt_msgs::GraphSlamAgent agent
Class template that provides a wrapper around the MRPT CGraphSlamEngine class template and implements...
size_t m_graph_nodes_last_size
Last known size of the m_nodes map.
neighbors_t m_neighbors
GraphSlamAgent instance pointer to TNeighborAgentProps.
size_t m_nodes_to_laser_scans2D_last_size
Last known size of the m_nodes_to_laser_scans2D map.
ros::AsyncSpinner cm_graph_async_spinner
AsyncSpinner that is used to query the CM-Graph service in case a new request arrives.
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::poses::CPose2D tf_self_to_neighbor_first_integrated_pose
CPose2D connecting own graph origin to neighbor first received and integrated node....
Struct responsible for holding properties (nodeIDs, node positions, LaserScans) that have been regist...
Class responsible of handling the network communication between SLAM agents in the Multi-Robot graphS...
std::map< TNodeID, bool > nodeID_to_is_integrated
Have I already integrated this node in my graph?
std::map< TNeighborAgentProps *, bool > m_neighbor_to_found_initial_tf
Map from neighbor instance to transformation from own to neighbor's graph.
std::map< TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > nodes_to_scans2D_t
const neighbors_t & getVecOfNeighborAgentProps() const
std::string m_last_regd_nodes_topic
Name of the topic that the last X registered nodes + positions are going to be published at.
CGraphSlamEngine_MR< GRAPH_T > & engine
mrpt::maps::COccupancyGridMap2D::Ptr gridmap_cached
Pointer to the gridmap object of the neighbor.
GRAPH_T::global_poses_t poses
Poses that I have received from this graphSLAM agent.
std::vector< std::vector< TNodeID > > partitions_t
std::string getAgentNs() const
std::pair< TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > MRPT_NodeIDWithLaserScan
ros::Publisher m_list_neighbors_pub
ros::Subscriber last_regd_id_scan_sub
std::string last_regd_id_scan_topic
mrpt::graphslam::deciders::CEdgeRegistrationDecider_MR< GRAPH_T > edge_reg_mr_t
int num_last_regd_nodes
Max number of last registered NodeIDs + corresponding positions to publish.
CGraphSlamEngine_ROS< GRAPH_T > parent_t
bool conservative_find_initial_tfs_to_neighbors
Be conservative when it comes to deciding the initial transformation of own graph with regards to gra...
ros::ServiceServer m_cm_graph_srvserver
ros::Publisher m_last_regd_nodes_pub
Publisher of the last registered nodeIDs and positions.
mrpt::graphslam::CGraphSlamEngine derived class for executing multi-robot graphSLAM
std::string m_sec_alignment_params
bool m_registered_multiple_nodes
Indicates whether multiple nodes were just registered. Used for checking correct node registration in...
constraint_t::type_value pose_t
mrpt::graphslam::detail::CConnectionManager m_conn_manager
CConnectionManager instance.
double m_offset_y_namespace
Edge Registration Decider virtual method.
GRAPH_T::constraint_t constraint_t
std::vector< path_t > paths_t
mrpt::graphs::detail::THypothesis< GRAPH_T > hypot_t
std::string last_regd_nodes_topic
std::string cm_graph_service
GRAPH_T::global_pose_t global_pose_t
std::string m_list_neighbors_topic
Name of topic at which we publish information about the agents that we can currently communicate with...