Public Member Functions | Public Attributes
plannerMapServer Class Reference

loads and updates a map from an overhead camera More...

#include <plannerMapServer.h>

List of all members.

Public Member Functions

void loadMapFromMat (nav_msgs::GetMap::Response *resp, cv::Mat *opencvimg, double res, bool negate, double occThresh, double freeThresh, double *origin)
bool mapCallback (nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
void mapUpdateCallback (const sensor_msgs::Image &mapImg)
 plannerMapServer ()

Public Attributes

bool deprecated
std::string frameID
double freeThresh
std::string mapfname
ros::Subscriber mapImageSubscriber
ros::Publisher mapPublisher
nav_msgs::GetMap::Response mapResponse
nav_msgs::MapMetaData metaDataMessage
ros::Publisher metadataPublisher
ros::NodeHandle n
int negate
double occThresh
double origin [3]
double resolution
ros::ServiceServer service

Detailed Description

loads and updates a map from an overhead camera

This class periodically updates a map from an overhead camera. The map is published for use in creating occupancy grids and path planning. The map is created from the opencv Mat image format.

Definition at line 57 of file plannerMapServer.h.


Constructor & Destructor Documentation

Constructor

Definition at line 46 of file plannerMapServer.cpp.


Member Function Documentation

void plannerMapServer::loadMapFromMat ( nav_msgs::GetMap::Response *  resp,
cv::Mat *  opencvimg,
double  res,
bool  negate,
double  occThresh,
double  freeThresh,
double *  origin 
)

Load map from an opencv Mat

Parameters:
respresponse for the map
opencvimgthe image to load
resmap resolution
negateswitch the meaning of black and white pixels if true
occThreshoccupied threshold
freeThreshfree threshold
originmap origin

Definition at line 147 of file plannerMapServer.cpp.

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

Callback invoked when someone requests our service

Parameters:
reqservice request
resservice response
Returns:
true on success

Definition at line 138 of file plannerMapServer.cpp.

void plannerMapServer::mapUpdateCallback ( const sensor_msgs::Image &  mapImg)

Callback to update the map

Parameters:
mapImgthe new map image

Definition at line 123 of file plannerMapServer.cpp.


Member Data Documentation

Definition at line 65 of file plannerMapServer.h.

Definition at line 66 of file plannerMapServer.h.

Definition at line 61 of file plannerMapServer.h.

Definition at line 67 of file plannerMapServer.h.

Definition at line 72 of file plannerMapServer.h.

Definition at line 69 of file plannerMapServer.h.

nav_msgs::GetMap::Response plannerMapServer::mapResponse

Definition at line 73 of file plannerMapServer.h.

nav_msgs::MapMetaData plannerMapServer::metaDataMessage

Definition at line 74 of file plannerMapServer.h.

Definition at line 70 of file plannerMapServer.h.

Definition at line 68 of file plannerMapServer.h.

Definition at line 60 of file plannerMapServer.h.

Definition at line 62 of file plannerMapServer.h.

Definition at line 64 of file plannerMapServer.h.

Definition at line 63 of file plannerMapServer.h.

Definition at line 71 of file plannerMapServer.h.


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


youbot_overhead_localization
Author(s): David Kent
autogenerated on Thu Jan 2 2014 12:14:20