Class implementing a thread generating an occupancy grid. More...
#include <ThreadGrid.h>

Public Member Functions | |
| ThreadGrid (obvious::TsdGrid *grid, ros::NodeHandle *const nh, const double xOffset, const double yOffset) | |
| virtual | ~ThreadGrid () |
Protected Member Functions | |
| virtual void | eventLoop (void) |
Private Member Functions | |
| bool | getMapServCallBack (nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res) |
Private Attributes | |
| double | _cellSize |
| ros::ServiceServer | _getMapServ |
| double * | _gridCoords |
| ros::Publisher | _gridPub |
| unsigned int | _height |
| bool | _objectInflation |
| unsigned int | _objInflateFactor |
| nav_msgs::OccupancyGrid * | _occGrid |
| char * | _occGridContent |
| unsigned int | _width |
Class implementing a thread generating an occupancy grid.
Definition at line 20 of file ThreadGrid.h.
| ohm_tsd_slam::ThreadGrid::ThreadGrid | ( | obvious::TsdGrid * | grid, |
| ros::NodeHandle *const | nh, | ||
| const double | xOffset, | ||
| const double | yOffset | ||
| ) |
Constructor
| grid | Representation |
| nh | Ros nodehandle |
| parentNode | Pointer to main mapping instance |
Definition at line 12 of file ThreadGrid.cpp.
| ohm_tsd_slam::ThreadGrid::~ThreadGrid | ( | ) | [virtual] |
Destructor
Definition at line 56 of file ThreadGrid.cpp.
| void ohm_tsd_slam::ThreadGrid::eventLoop | ( | void | ) | [protected, virtual] |
eventLoop Thread event loop
Implements ohm_tsd_slam::ThreadSLAM.
Definition at line 65 of file ThreadGrid.cpp.
| bool ohm_tsd_slam::ThreadGrid::getMapServCallBack | ( | nav_msgs::GetMap::Request & | req, |
| nav_msgs::GetMap::Response & | res | ||
| ) | [private] |
getMapServCallBack Ros service callback method for the get map service
| req | Request |
| res | Response |
Definition at line 112 of file ThreadGrid.cpp.
double ohm_tsd_slam::ThreadGrid::_cellSize [private] |
Grid resolution
Definition at line 89 of file ThreadGrid.h.
Ros get map service
Definition at line 64 of file ThreadGrid.h.
double* ohm_tsd_slam::ThreadGrid::_gridCoords [private] |
Buffer for grid coordinates
Definition at line 74 of file ThreadGrid.h.
Occupancy grid publisher
Definition at line 94 of file ThreadGrid.h.
unsigned int ohm_tsd_slam::ThreadGrid::_height [private] |
Grid dimension
Definition at line 84 of file ThreadGrid.h.
bool ohm_tsd_slam::ThreadGrid::_objectInflation [private] |
Object inflation control flag
Definition at line 104 of file ThreadGrid.h.
unsigned int ohm_tsd_slam::ThreadGrid::_objInflateFactor [private] |
Object inflation factor
Definition at line 99 of file ThreadGrid.h.
nav_msgs::OccupancyGrid* ohm_tsd_slam::ThreadGrid::_occGrid [private] |
Occupancy grid
Definition at line 59 of file ThreadGrid.h.
char* ohm_tsd_slam::ThreadGrid::_occGridContent [private] |
Buffer for occupancy grid content
Definition at line 69 of file ThreadGrid.h.
unsigned int ohm_tsd_slam::ThreadGrid::_width [private] |
Grid dimension
Definition at line 79 of file ThreadGrid.h.