#include <map_republisher.h>
Public Member Functions | |
MapRepublisher () | |
void | publishMap () |
Private Member Functions | |
bool | mapServiceCallback (nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res) |
void | obstacleCallback (const carl_navigation::BlockedCells &grid) |
void | staticMapCallback (const nav_msgs::OccupancyGrid &map) |
Private Attributes | |
nav_msgs::OccupancyGrid | combinedMap |
ros::ServiceServer | getMapServer |
ros::Publisher | mapMetaDataPublisher |
ros::Publisher | mapPublisher |
ros::Subscriber | mapSubscriber |
int | mapSubscribers |
int | metaDataSubscribers |
ros::NodeHandle | n |
std::vector< geometry_msgs::Point > | obstacleCells |
std::vector< geometry_msgs::Point > | obstacleEdges |
ros::Subscriber | obstacleGridSubscriber |
nav_msgs::OccupancyGrid | staticMap |
bool | staticMapInitialized |
Definition at line 15 of file map_republisher.h.
Constructor
Definition at line 13 of file map_republisher.cpp.
bool MapRepublisher::mapServiceCallback | ( | nav_msgs::GetMap::Request & | req, |
nav_msgs::GetMap::Response & | res | ||
) | [private] |
Map service callback
req | service request |
res | service response |
Definition at line 30 of file map_republisher.cpp.
void MapRepublisher::obstacleCallback | ( | const carl_navigation::BlockedCells & | grid | ) | [private] |
Callback for the obstacle grid, will republish the map with obstacle data added to the static map
grid | obstacles found by an external vision system |
Definition at line 53 of file map_republisher.cpp.
void MapRepublisher::publishMap | ( | ) |
Republish the map or the map metadata if the number of subscribers changes
Definition at line 73 of file map_republisher.cpp.
void MapRepublisher::staticMapCallback | ( | const nav_msgs::OccupancyGrid & | map | ) | [private] |
Callback for static map, will republish the map with obstacle data added if obstacle data has been previously received
map | static map from map_server |
Definition at line 36 of file map_republisher.cpp.
nav_msgs::OccupancyGrid MapRepublisher::combinedMap [private] |
Definition at line 44 of file map_republisher.h.
Definition at line 38 of file map_republisher.h.
Definition at line 36 of file map_republisher.h.
ros::Publisher MapRepublisher::mapPublisher [private] |
Definition at line 35 of file map_republisher.h.
ros::Subscriber MapRepublisher::mapSubscriber [private] |
Definition at line 32 of file map_republisher.h.
int MapRepublisher::mapSubscribers [private] |
Definition at line 40 of file map_republisher.h.
int MapRepublisher::metaDataSubscribers [private] |
Definition at line 41 of file map_republisher.h.
ros::NodeHandle MapRepublisher::n [private] |
Definition at line 30 of file map_republisher.h.
std::vector<geometry_msgs::Point> MapRepublisher::obstacleCells [private] |
Definition at line 46 of file map_republisher.h.
std::vector<geometry_msgs::Point> MapRepublisher::obstacleEdges [private] |
Definition at line 47 of file map_republisher.h.
Definition at line 33 of file map_republisher.h.
nav_msgs::OccupancyGrid MapRepublisher::staticMap [private] |
Definition at line 45 of file map_republisher.h.
bool MapRepublisher::staticMapInitialized [private] |
Definition at line 48 of file map_republisher.h.