Public Member Functions | Private Member Functions | Private Attributes
MapServer Class Reference

List of all members.

Public Member Functions

 MapServer (const std::string &fname, double res)

Private Member Functions

bool mapCallback (nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)

Private Attributes

bool deprecated
ros::Publisher map_pub
nav_msgs::GetMap::Response map_resp_
nav_msgs::MapMetaData meta_data_message_
ros::Publisher metadata_pub
ros::NodeHandle n
ros::ServiceServer service

Detailed Description

Definition at line 59 of file main.cpp.


Constructor & Destructor Documentation

MapServer::MapServer ( const std::string &  fname,
double  res 
) [inline]

Trivial constructor

Definition at line 63 of file main.cpp.


Member Function Documentation

bool MapServer::mapCallback ( nav_msgs::GetMap::Request &  req,
nav_msgs::GetMap::Response &  res 
) [inline, private]

Callback invoked when someone requests our service

Definition at line 198 of file main.cpp.


Member Data Documentation

bool MapServer::deprecated [private]

Definition at line 195 of file main.cpp.

Definition at line 192 of file main.cpp.

nav_msgs::GetMap::Response MapServer::map_resp_ [private]

Definition at line 213 of file main.cpp.

nav_msgs::MapMetaData MapServer::meta_data_message_ [private]

The map data is cached here, to be sent out to service callers

Definition at line 212 of file main.cpp.

Definition at line 193 of file main.cpp.

Definition at line 191 of file main.cpp.

Definition at line 194 of file main.cpp.


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


map_server
Author(s): Brian Gerkey, Tony Pratkanis, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:45:59