42 #include <forward_list> 44 #include <unordered_map> 47 #include <geometry_msgs/Pose.h> 48 #include <map_msgs/OccupancyGridUpdate.h> 49 #include <nav_msgs/OccupancyGrid.h> 51 #include <boost/thread.hpp> 87 std::unordered_map<std::string, MapSubscription*>
robots_;
95 std::string robotNameFromTopic(
const std::string& topic);
97 bool getInitPose(
const std::string& name, geometry_msgs::Transform& pose);
99 void fullMapUpdate(
const nav_msgs::OccupancyGrid::ConstPtr& msg,
101 void partialMapUpdate(
const map_msgs::OccupancyGridUpdate::ConstPtr& msg,
108 void executetopicSubscribing();
109 void executemapMerging();
110 void executeposeEstimation();
112 void topicSubscribing();
118 void poseEstimation();
combine_grids::MergingPipeline pipeline_
Pipeline for merging overlapping occupancy grids.
size_t subscriptions_size_
std::unordered_map< std::string, MapSubscription * > robots_
std::string robot_map_updates_topic_
ros::Subscriber map_updates_sub
std::forward_list< MapSubscription > subscriptions_
std::string robot_namespace_
nav_msgs::OccupancyGrid::ConstPtr readonly_map
geometry_msgs::Transform initial_pose
std::string robot_map_topic_
double confidence_treshold_
nav_msgs::OccupancyGrid::Ptr writable_map
ros::Publisher merged_map_publisher_
boost::shared_mutex subscriptions_mutex_
std::mutex pipeline_mutex_