Public Member Functions | Private Types | Private Member Functions | Private Attributes
map_merge::MapMerging Class Reference

#include <map_merge.h>

List of all members.

Public Member Functions

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

Private Types

typedef std::vector
< std::reference_wrapper
< nav_msgs::OccupancyGrid > > 
grids_view_t

Private Member Functions

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

Private Attributes

grids_view_t all_grids_view_
double confidence_treshold_
double discovery_rate_
grids_view_t estimated_grids_view_
double estimation_rate_
bool have_initial_poses_
std::forward_list< PosedMapmaps_
size_t maps_size_
nav_msgs::OccupancyGrid merged_map_
ros::Publisher merged_map_publisher_
boost::shared_mutex merging_mutex_
double merging_rate_
ros::NodeHandle node_
std::string robot_map_topic_
std::string robot_map_updates_topic_
std::string robot_namespace_
std::unordered_map
< std::string, PosedMap * > 
robots_

Detailed Description

Definition at line 65 of file map_merge.h.


Member Typedef Documentation

typedef std::vector<std::reference_wrapper<nav_msgs::OccupancyGrid> > map_merge::MapMerging::grids_view_t [private]

Definition at line 91 of file map_merge.h.


Constructor & Destructor Documentation

Definition at line 54 of file map_merge.cpp.


Member Function Documentation

Definition at line 401 of file map_merge.cpp.

Definition at line 419 of file map_merge.cpp.

Definition at line 410 of file map_merge.cpp.

void map_merge::MapMerging::fullMapUpdate ( const nav_msgs::OccupancyGrid::ConstPtr &  msg,
PosedMap map 
) [private]

Definition at line 252 of file map_merge.cpp.

bool map_merge::MapMerging::getInitPose ( const std::string &  name,
geometry_msgs::Pose pose 
) [private]

Definition at line 378 of file map_merge.cpp.

Definition at line 354 of file map_merge.cpp.

Definition at line 160 of file map_merge.cpp.

void map_merge::MapMerging::partialMapUpdate ( const map_msgs::OccupancyGridUpdate::ConstPtr &  msg,
PosedMap map 
) [private]

Definition at line 290 of file map_merge.cpp.

Estimates initial positions of grids.

Relevant only if initial poses are not known

Definition at line 188 of file map_merge.cpp.

std::string map_merge::MapMerging::robotNameFromTopic ( const std::string &  topic) [private]

Definition at line 335 of file map_merge.cpp.

Definition at line 434 of file map_merge.cpp.

Definition at line 82 of file map_merge.cpp.


Member Data Documentation

Definition at line 93 of file map_merge.h.

Definition at line 74 of file map_merge.h.

Definition at line 72 of file map_merge.h.

Definition at line 96 of file map_merge.h.

Definition at line 73 of file map_merge.h.

Definition at line 78 of file map_merge.h.

std::forward_list<PosedMap> map_merge::MapMerging::maps_ [private]

Definition at line 87 of file map_merge.h.

Definition at line 88 of file map_merge.h.

nav_msgs::OccupancyGrid map_merge::MapMerging::merged_map_ [private]

Definition at line 81 of file map_merge.h.

Definition at line 82 of file map_merge.h.

boost::shared_mutex map_merge::MapMerging::merging_mutex_ [private]

Definition at line 100 of file map_merge.h.

Definition at line 71 of file map_merge.h.

Definition at line 68 of file map_merge.h.

Definition at line 75 of file map_merge.h.

Definition at line 76 of file map_merge.h.

Definition at line 77 of file map_merge.h.

std::unordered_map<std::string, PosedMap*> map_merge::MapMerging::robots_ [private]

Definition at line 85 of file map_merge.h.


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


map_merge
Author(s): Jiri Horner
autogenerated on Sun Mar 26 2017 03:48:10