surface_history_recorder.h
Go to the documentation of this file.
00001 #ifndef _SURFACE_PERCEPTION_SURFACE_HISTORY_RECORDER_H_
00002 #define _SURFACE_PERCEPTION_SURFACE_HISTORY_RECORDER_H_
00003 
00004 #include <ctime>
00005 #include <map>
00006 
00007 #include "pcl/PointIndices.h"
00008 #include "pcl/point_cloud.h"
00009 #include "pcl/point_types.h"
00010 
00011 namespace surface_perception {
00052 class SurfaceHistoryRecorder {
00053  public:
00065   void Record(size_t id, const pcl::PointCloud<pcl::PointXYZRGB>::Ptr& cloud,
00066               const pcl::PointIndices::Ptr& indices, size_t iteration);
00067 
00079   void Update(size_t old_id, size_t new_id,
00080               const pcl::PointCloud<pcl::PointXYZRGB>::Ptr& cloud,
00081               const pcl::PointIndices::Ptr& indices, size_t iteration);
00082 
00090   void GetCloudHistory(
00091       size_t id, pcl::PointCloud<pcl::PointXYZRGB>::Ptr output_cloud) const;
00092 
00101   void GetClock(size_t id, clock_t* clock_ptr) const;
00102 
00107   void GetIteration(size_t id, size_t* iteration_ptr) const;
00108 
00109  private:
00110   std::map<size_t, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> cloud_history_;
00111   std::map<size_t, clock_t> time_history_;
00112   std::map<size_t, size_t> iteration_history_;
00113 };
00114 }  // namespace surface_perception
00115 
00116 #endif  // _SURFACE_PERCEPTION_SURFACE_HISTORY_RECORDER_H_


surface_perception
Author(s): Yu-Tang Peng
autogenerated on Thu Jun 6 2019 17:36:21