Public Member Functions | Private Member Functions | Private Attributes | List of all members
map_merge::MapMerge Class Reference

#include <map_merge.h>

Public Member Functions

void executemapMerging ()
 
void executeposeEstimation ()
 
void executetopicSubscribing ()
 
 MapMerge ()
 
void mapMerging ()
 
void poseEstimation ()
 Estimates initial positions of grids. More...
 
void spin ()
 
void topicSubscribing ()
 

Private Member Functions

void fullMapUpdate (const nav_msgs::OccupancyGrid::ConstPtr &msg, MapSubscription &map)
 
bool getInitPose (const std::string &name, geometry_msgs::Transform &pose)
 
bool isRobotMapTopic (const ros::master::TopicInfo &topic)
 
void partialMapUpdate (const map_msgs::OccupancyGridUpdate::ConstPtr &msg, MapSubscription &map)
 
std::string robotNameFromTopic (const std::string &topic)
 

Private Attributes

double confidence_threshold_
 
double discovery_rate_
 
double estimation_rate_
 
bool have_initial_poses_
 
ros::Publisher merged_map_publisher_
 
double merging_rate_
 
ros::NodeHandle node_
 
combine_grids::MergingPipeline pipeline_
 
std::mutex pipeline_mutex_
 
std::string robot_map_topic_
 
std::string robot_map_updates_topic_
 
std::string robot_namespace_
 
std::unordered_map< std::string, MapSubscription * > robots_
 
std::forward_list< MapSubscriptionsubscriptions_
 
boost::shared_mutex subscriptions_mutex_
 
size_t subscriptions_size_
 
std::string world_frame_
 

Detailed Description

Definition at line 68 of file map_merge.h.

Constructor & Destructor Documentation

◆ MapMerge()

map_merge::MapMerge::MapMerge ( )

Definition at line 47 of file map_merge.cpp.

Member Function Documentation

◆ executemapMerging()

void map_merge::MapMerge::executemapMerging ( )

Definition at line 351 of file map_merge.cpp.

◆ executeposeEstimation()

void map_merge::MapMerge::executeposeEstimation ( )

Definition at line 369 of file map_merge.cpp.

◆ executetopicSubscribing()

void map_merge::MapMerge::executetopicSubscribing ( )

Definition at line 360 of file map_merge.cpp.

◆ fullMapUpdate()

void map_merge::MapMerge::fullMapUpdate ( const nav_msgs::OccupancyGrid::ConstPtr &  msg,
MapSubscription map 
)
private

Definition at line 207 of file map_merge.cpp.

◆ getInitPose()

bool map_merge::MapMerge::getInitPose ( const std::string &  name,
geometry_msgs::Transform &  pose 
)
private

Definition at line 325 of file map_merge.cpp.

◆ isRobotMapTopic()

bool map_merge::MapMerge::isRobotMapTopic ( const ros::master::TopicInfo topic)
private

Definition at line 301 of file map_merge.cpp.

◆ mapMerging()

void map_merge::MapMerge::mapMerging ( )

Definition at line 146 of file map_merge.cpp.

◆ partialMapUpdate()

void map_merge::MapMerge::partialMapUpdate ( const map_msgs::OccupancyGridUpdate::ConstPtr &  msg,
MapSubscription map 
)
private

Definition at line 222 of file map_merge.cpp.

◆ poseEstimation()

void map_merge::MapMerge::poseEstimation ( )

Estimates initial positions of grids.

Relevant only if initial poses are not known

Definition at line 187 of file map_merge.cpp.

◆ robotNameFromTopic()

std::string map_merge::MapMerge::robotNameFromTopic ( const std::string &  topic)
private

Definition at line 295 of file map_merge.cpp.

◆ spin()

void map_merge::MapMerge::spin ( )

Definition at line 384 of file map_merge.cpp.

◆ topicSubscribing()

void map_merge::MapMerge::topicSubscribing ( )

Definition at line 73 of file map_merge.cpp.

Member Data Documentation

◆ confidence_threshold_

double map_merge::MapMerge::confidence_threshold_
private

Definition at line 77 of file map_merge.h.

◆ discovery_rate_

double map_merge::MapMerge::discovery_rate_
private

Definition at line 75 of file map_merge.h.

◆ estimation_rate_

double map_merge::MapMerge::estimation_rate_
private

Definition at line 76 of file map_merge.h.

◆ have_initial_poses_

bool map_merge::MapMerge::have_initial_poses_
private

Definition at line 82 of file map_merge.h.

◆ merged_map_publisher_

ros::Publisher map_merge::MapMerge::merged_map_publisher_
private

Definition at line 85 of file map_merge.h.

◆ merging_rate_

double map_merge::MapMerge::merging_rate_
private

Definition at line 74 of file map_merge.h.

◆ node_

ros::NodeHandle map_merge::MapMerge::node_
private

Definition at line 71 of file map_merge.h.

◆ pipeline_

combine_grids::MergingPipeline map_merge::MapMerge::pipeline_
private

Definition at line 92 of file map_merge.h.

◆ pipeline_mutex_

std::mutex map_merge::MapMerge::pipeline_mutex_
private

Definition at line 93 of file map_merge.h.

◆ robot_map_topic_

std::string map_merge::MapMerge::robot_map_topic_
private

Definition at line 78 of file map_merge.h.

◆ robot_map_updates_topic_

std::string map_merge::MapMerge::robot_map_updates_topic_
private

Definition at line 79 of file map_merge.h.

◆ robot_namespace_

std::string map_merge::MapMerge::robot_namespace_
private

Definition at line 80 of file map_merge.h.

◆ robots_

std::unordered_map<std::string, MapSubscription*> map_merge::MapMerge::robots_
private

Definition at line 87 of file map_merge.h.

◆ subscriptions_

std::forward_list<MapSubscription> map_merge::MapMerge::subscriptions_
private

Definition at line 89 of file map_merge.h.

◆ subscriptions_mutex_

boost::shared_mutex map_merge::MapMerge::subscriptions_mutex_
private

Definition at line 91 of file map_merge.h.

◆ subscriptions_size_

size_t map_merge::MapMerge::subscriptions_size_
private

Definition at line 90 of file map_merge.h.

◆ world_frame_

std::string map_merge::MapMerge::world_frame_
private

Definition at line 81 of file map_merge.h.


The documentation for this class was generated from the following files:


map_merge
Author(s): Jiri Horner
autogenerated on Mon Feb 28 2022 22:46:02