Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
ohm_tsd_slam::ThreadGrid Class Reference

Class implementing a thread generating an occupancy grid. More...

#include <ThreadGrid.h>

Inheritance diagram for ohm_tsd_slam::ThreadGrid:
Inheritance graph
[legend]

List of all members.

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

Detailed Description

Class implementing a thread generating an occupancy grid.

Author:
Philipp Koch, Stefan May

Definition at line 20 of file ThreadGrid.h.


Constructor & Destructor Documentation

ohm_tsd_slam::ThreadGrid::ThreadGrid ( obvious::TsdGrid *  grid,
ros::NodeHandle *const  nh,
const double  xOffset,
const double  yOffset 
)

Constructor

Parameters:
gridRepresentation
nhRos nodehandle
parentNodePointer to main mapping instance

Definition at line 12 of file ThreadGrid.cpp.

Destructor

Definition at line 56 of file ThreadGrid.cpp.


Member Function Documentation

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

Parameters:
reqRequest
resResponse
Returns:
true in case of success

Definition at line 112 of file ThreadGrid.cpp.


Member Data Documentation

Grid resolution

Definition at line 89 of file ThreadGrid.h.

Ros get map service

Definition at line 64 of file ThreadGrid.h.

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.

Object inflation control flag

Definition at line 104 of file ThreadGrid.h.

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.

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.


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


ohm_tsd_slam
Author(s): Philipp Koch, Stefan May, Markus Kühn
autogenerated on Thu Jun 6 2019 17:41:12