OctomapInterface.h
Go to the documentation of this file.
00001 /*
00002  * octomapinterface.h
00003  *
00004  *  Created on: Dec 26, 2012
00005  *      Author: slynen
00006  */
00007 
00008 #ifndef PCLINTERFACE_H_
00009 #define PCLINTERFACE_H_
00010 #include <ptam/MapPoint.h>
00011 #include <ptam/KeyFrame.h>
00012 #include <set>
00013 
00014 class OctoMapInterface
00015 {
00016 private:
00017   ros::NodeHandle& nh_;
00018   ros::Publisher pub_scan_;
00019   ros::Publisher pub_points_;
00020 
00021   std::set<MapPoint::Ptr> localUpdateQueue_; //to collect updates before publishing them all at once
00022 
00023   unsigned int kfseq_;
00024   unsigned int pointseq_;
00025 public:
00026   OctoMapInterface( ros::NodeHandle& nh);
00027   virtual ~OctoMapInterface();
00028 
00029   void addKeyFrame(KeyFrame::Ptr k);
00030   void updatePoint(MapPoint::Ptr p);
00031   void updatePoints(std::set<MapPoint::Ptr>& p);
00032   void deletePoint(MapPoint::Ptr p);
00033 
00034 protected:
00035   void publishPointUpdateFromQueue();
00036 
00037 };
00038 
00039 #endif /* PCLINTERFACE_H_ */


ptam
Author(s): Stephan Weiss, Markus Achtelik, Simon Lynen
autogenerated on Tue Jan 7 2014 11:12:22