Go to the documentation of this file.
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_;
97 bool getInitPose(
const std::string& name, geometry_msgs::Transform& pose);
99 void fullMapUpdate(
const nav_msgs::OccupancyGrid::ConstPtr& msg,
nav_msgs::OccupancyGrid::Ptr writable_map
bool isRobotMapTopic(const ros::master::TopicInfo &topic)
Pipeline for merging overlapping occupancy grids.
std::string robot_namespace_
size_t subscriptions_size_
combine_grids::MergingPipeline pipeline_
nav_msgs::OccupancyGrid::ConstPtr readonly_map
std::unordered_map< std::string, MapSubscription * > robots_
std::string robot_map_updates_topic_
void poseEstimation()
Estimates initial positions of grids.
std::string robotNameFromTopic(const std::string &topic)
std::mutex pipeline_mutex_
boost::shared_mutex subscriptions_mutex_
void executetopicSubscribing()
std::string robot_map_topic_
bool getInitPose(const std::string &name, geometry_msgs::Transform &pose)
void partialMapUpdate(const map_msgs::OccupancyGridUpdate::ConstPtr &msg, MapSubscription &map)
std::forward_list< MapSubscription > subscriptions_
ros::Publisher merged_map_publisher_
double confidence_threshold_
void fullMapUpdate(const nav_msgs::OccupancyGrid::ConstPtr &msg, MapSubscription &map)
geometry_msgs::Transform initial_pose
void executeposeEstimation()
ros::Subscriber map_updates_sub
map_merge
Author(s): Jiri Horner
autogenerated on Wed Mar 2 2022 00:32:15