ThreadMapping.h
Go to the documentation of this file.
00001 #ifndef THREADMAPPING_H_
00002 #define THREADMAPPING_H_
00003 
00004 #include "ThreadSLAM.h"
00005 
00006 #include "sensor_msgs/LaserScan.h"
00007 
00008 #include "obvision/reconstruct/grid/SensorPolar2D.h"
00009 #include "obvision/reconstruct/grid/TsdGrid.h"
00010 
00011 #include <boost/thread.hpp>
00012 #include <queue>
00013 
00014 namespace ohm_tsd_slam
00015 {
00016 
00017 class SlamNode;
00018 
00024 class ThreadMapping : public ThreadSLAM
00025 {
00026 public:
00027 
00032   ThreadMapping(obvious::TsdGrid* grid);
00033 
00037   virtual ~ThreadMapping();
00038 
00044   void queuePush(obvious::SensorPolar2D* sensor);
00045 
00051   bool initialized(void);
00052 
00058   void initPush(obvious::SensorPolar2D* sensor);
00059 
00060 protected:
00061 
00066   virtual void eventLoop(void);
00067 
00068 private:
00069 
00073   std::queue<obvious::SensorPolar2D*> _sensors;
00074 
00078   boost::mutex _pushMutex;
00079 
00083   bool _initialized;
00084 };
00085 
00086 } /* namespace */
00087 
00088 #endif /* THREADMAPPING_H_ */


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