Public Member Functions | Private Member Functions | Private Attributes
ohm_tsd_slam::SlamNode Class Reference

Main node management of the 2D SLAM. More...

#include <SlamNode.h>

List of all members.

Public Member Functions

 SlamNode (void)
void start (void)
virtual ~SlamNode ()

Private Member Functions

void run (void)
void timedGridPub (void)

Private Attributes

obvious::TsdGrid * _grid
ros::Duration_gridInterval
std::vector< ThreadLocalize * > _localizers
ros::Rate_loopRate
ros::NodeHandle _nh
std::vector< ros::Subscriber_subsLaser
ThreadGrid_threadGrid
ThreadMapping_threadMapping
double _xOffFactor
double _yOffFactor

Detailed Description

Main node management of the 2D SLAM.

Author:
Philipp Koch

Definition at line 27 of file SlamNode.h.


Constructor & Destructor Documentation

Default constructor

Definition at line 18 of file SlamNode.cpp.

Destructor

Definition at line 99 of file SlamNode.cpp.


Member Function Documentation

void ohm_tsd_slam::SlamNode::run ( void  ) [private]

run Main SLAM method

Definition at line 134 of file SlamNode.cpp.

void ohm_tsd_slam::SlamNode::start ( void  ) [inline]

start Method to start the SLAM

Definition at line 45 of file SlamNode.h.

void ohm_tsd_slam::SlamNode::timedGridPub ( void  ) [private]

timedGridPub Enables occupancy grid thread with certain frequency

Definition at line 123 of file SlamNode.cpp.


Member Data Documentation

obvious::TsdGrid* ohm_tsd_slam::SlamNode::_grid [private]

Representation

Definition at line 68 of file SlamNode.h.

Rate used for occupancy grid generation

Definition at line 93 of file SlamNode.h.

Localizing threads

Definition at line 109 of file SlamNode.h.

Desired loop rate

Definition at line 98 of file SlamNode.h.

Main node handle

Definition at line 63 of file SlamNode.h.

Ros laser subscriber

Definition at line 103 of file SlamNode.h.

Grid thread instance

Definition at line 78 of file SlamNode.h.

Mapping thread instance

Definition at line 73 of file SlamNode.h.

X starting offset factor

Definition at line 83 of file SlamNode.h.

Y starting offset factor

Definition at line 88 of file SlamNode.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