Public Member Functions | Private Member Functions | Private Attributes | List of all members
stdr_server::MapServer Class Reference

Implements the STDR map server functionalities. More...

#include <map_server.h>

Public Member Functions

 MapServer (const std::string &fname)
 Constructor by filename. More...
 
 MapServer (const nav_msgs::OccupancyGrid &map)
 Constructor by occupancy grid map. More...
 

Private Member Functions

void publishData ()
 Publishes the map data and metadata. More...
 
void publishTransform (const ros::TimerEvent &ev)
 Publishes the map to map_static transform. More...
 

Private Attributes

nav_msgs::OccupancyGrid map_
 
ros::Publisher map_pub
 ROS publisher for posting the map metadata. More...
 
nav_msgs::MapMetaData meta_data_message_
 ROS occupancy grid message. More...
 
ros::Publisher metadata_pub
 ROS timer for tf posting. More...
 
ros::NodeHandle n
 < The ROS node handle More...
 
tf::TransformBroadcaster tfBroadcaster
 ROS map metadata message. More...
 
ros::Timer tfTimer
 ROS tf broadcaster. More...
 

Detailed Description

Implements the STDR map server functionalities.

Definition at line 39 of file map_server.h.

Constructor & Destructor Documentation

MapServer::MapServer ( const std::string &  fname)
explicit

Constructor by filename.

Parameters
fname[const std::string&] The file name
Returns
void

Definition at line 31 of file map_server.cpp.

MapServer::MapServer ( const nav_msgs::OccupancyGrid &  map)
explicit

Constructor by occupancy grid map.

Parameters
map[const nav_msgs::OccupancyGrid&] The occupancy grid map
Returns
void

Definition at line 46 of file map_server.cpp.

Member Function Documentation

void MapServer::publishData ( void  )
private

Publishes the map data and metadata.

Returns
void

< 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.

Parameters
ev[const ros::TimerEvent&] A ROS timer event
Returns
void

Definition at line 80 of file map_server.cpp.

Member Data Documentation

nav_msgs::OccupancyGrid stdr_server::MapServer::map_
private

Definition at line 87 of file map_server.h.

ros::Publisher stdr_server::MapServer::map_pub
private

ROS publisher for posting the map metadata.

Definition at line 77 of file map_server.h.

nav_msgs::MapMetaData stdr_server::MapServer::meta_data_message_
private

ROS occupancy grid message.

Definition at line 85 of file map_server.h.

ros::Publisher stdr_server::MapServer::metadata_pub
private

ROS timer for tf posting.

Definition at line 79 of file map_server.h.

ros::NodeHandle stdr_server::MapServer::n
private

< The ROS node handle

ROS publisher for posting the map

Definition at line 75 of file map_server.h.

tf::TransformBroadcaster stdr_server::MapServer::tfBroadcaster
private

ROS map metadata message.

Definition at line 83 of file map_server.h.

ros::Timer stdr_server::MapServer::tfTimer
private

ROS tf broadcaster.

Definition at line 81 of file map_server.h.


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


stdr_server
Author(s): Chris Zalidis
autogenerated on Mon Jun 10 2019 15:15:07