Main node management of the 2D SLAM. More...
#include <SlamNode.h>
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 |
Main node management of the 2D SLAM.
Definition at line 27 of file SlamNode.h.
ohm_tsd_slam::SlamNode::SlamNode | ( | void | ) |
Default constructor
Definition at line 18 of file SlamNode.cpp.
ohm_tsd_slam::SlamNode::~SlamNode | ( | ) | [virtual] |
Destructor
Definition at line 99 of file SlamNode.cpp.
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.
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.
std::vector<ThreadLocalize*> ohm_tsd_slam::SlamNode::_localizers [private] |
Localizing threads
Definition at line 109 of file SlamNode.h.
ros::Rate* ohm_tsd_slam::SlamNode::_loopRate [private] |
Desired loop rate
Definition at line 98 of file SlamNode.h.
ros::NodeHandle ohm_tsd_slam::SlamNode::_nh [private] |
Main node handle
Definition at line 63 of file SlamNode.h.
std::vector<ros::Subscriber> ohm_tsd_slam::SlamNode::_subsLaser [private] |
Ros laser subscriber
Definition at line 103 of file SlamNode.h.
ThreadGrid* ohm_tsd_slam::SlamNode::_threadGrid [private] |
Grid thread instance
Definition at line 78 of file SlamNode.h.
Mapping thread instance
Definition at line 73 of file SlamNode.h.
double ohm_tsd_slam::SlamNode::_xOffFactor [private] |
X starting offset factor
Definition at line 83 of file SlamNode.h.
double ohm_tsd_slam::SlamNode::_yOffFactor [private] |
Y starting offset factor
Definition at line 88 of file SlamNode.h.