Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009 #ifndef PATCHMAP_H_
00010 #define PATCHMAP_H_
00011 #include <pcl/common/common_headers.h>
00012 #include <pcl/kdtree/impl/kdtree_flann.hpp>
00013 #include <surfacelet/SurfacePatch.h>
00014 #include <visualization_msgs/Marker.h>
00015 #include <visualization_msgs/MarkerArray.h>
00016 namespace surfacelet {
00017
00018 class PatchMap {
00019
00020 public:
00021
00022 PatchMap();
00023
00024 void insertScan(pcl::PointCloud<pcl::PointXYZ>& cloud, pcl::PointCloud<pcl::PointXYZ>& not_used_cloud);
00025 void insertScan(pcl::PointCloud<pcl::PointXYZ>& cloud, pcl::PointCloud<pcl::PointXYZ>& not_used_cloud,
00026 pcl::PointXYZ view_point);
00027 void constructNormalMarker(const std::string frame_id, visualization_msgs::MarkerArray& array) const;
00028 void constructMarker(const std::string frame_id, const std::vector<bool>& reachable,
00029 visualization_msgs::MarkerArray& array);
00030 void constructMarker(const std::string frame_id, const std::vector<bool>& reachable,
00031 const std::vector<bool>& collision, visualization_msgs::MarkerArray& array);
00032 void constructMarker(const std::string frame_id, visualization_msgs::MarkerArray& array);
00033
00034
00035 std::vector<SurfacePatch> map_;
00036
00037 private:
00038 void computePatchesFromCloud(pcl::PointCloud<pcl::PointXYZ>& cloud, const pcl::PointXYZ view_point,
00039 std::vector<SurfacePatch>& patches, pcl::PointCloud<pcl::PointXYZ>& not_used_cloud);
00040 bool pointRepresented(pcl::PointNormal p);
00041 bool searchPatchForPoint(pcl::PointXYZ p);
00042 bool generatePatch(const pcl::PointCloud<pcl::PointXYZ>& cloud, const pcl::PointXYZ view_point,
00043 const pcl::PointXYZ center, const std::vector<int>& mask, SurfacePatch& patch,
00044 std::vector<int>& removed_points);
00045
00046 pcl::KdTreeFLANN<SurfacePatch> tree_;
00047
00048 bool first_insert;
00049 float radius_;
00050 float ransac_distance_;
00051 int ransac_iterations_;
00052
00053 };
00054 }
00055
00056 #endif