Implements the STDR map server functionalities. More...
#include <map_server.h>
Public Member Functions | |
MapServer (const std::string &fname) | |
Constructor by filename. | |
MapServer (const nav_msgs::OccupancyGrid &map) | |
Constructor by occupancy grid map. | |
Private Member Functions | |
void | publishData () |
Publishes the map data and metadata. | |
void | publishTransform (const ros::TimerEvent &ev) |
Publishes the map to map_static transform. | |
Private Attributes | |
nav_msgs::OccupancyGrid | map_ |
ros::Publisher | map_pub |
ROS publisher for posting the map metadata. | |
nav_msgs::MapMetaData | meta_data_message_ |
ROS occupancy grid message. | |
ros::Publisher | metadata_pub |
ROS timer for tf posting. | |
ros::NodeHandle | n |
< The ROS node handle | |
tf::TransformBroadcaster | tfBroadcaster |
ROS map metadata message. | |
ros::Timer | tfTimer |
ROS tf broadcaster. |
Implements the STDR map server functionalities.
Definition at line 39 of file map_server.h.
MapServer::MapServer | ( | const std::string & | fname | ) | [explicit] |
Constructor by filename.
fname | [const std::string&] The file name |
Definition at line 31 of file map_server.cpp.
MapServer::MapServer | ( | const nav_msgs::OccupancyGrid & | map | ) | [explicit] |
Constructor by occupancy grid map.
map | [const nav_msgs::OccupancyGrid&] The occupancy grid map |
Definition at line 46 of file map_server.cpp.
void MapServer::publishData | ( | void | ) | [private] |
Publishes the map data and metadata.
< Latched publisher for metadata
< Latched publisher for data
Definition at line 60 of file map_server.cpp.
void MapServer::publishTransform | ( | const ros::TimerEvent & | ev | ) | [private] |
Publishes the map to map_static transform.
ev | [const ros::TimerEvent&] A ROS timer event |
Definition at line 80 of file map_server.cpp.
nav_msgs::OccupancyGrid stdr_server::MapServer::map_ [private] |
Definition at line 87 of file map_server.h.
ROS publisher for posting the map metadata.
Definition at line 78 of file map_server.h.
nav_msgs::MapMetaData stdr_server::MapServer::meta_data_message_ [private] |
ROS occupancy grid message.
Definition at line 86 of file map_server.h.
ROS timer for tf posting.
Definition at line 80 of file map_server.h.
ros::NodeHandle stdr_server::MapServer::n [private] |
ROS map metadata message.
Definition at line 84 of file map_server.h.
ros::Timer stdr_server::MapServer::tfTimer [private] |
ROS tf broadcaster.
Definition at line 82 of file map_server.h.