Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025 #ifndef _hole_detection_alg_h_
00026 #define _hole_detection_alg_h_
00027
00028 #include <iri_hole_detection/HoleDetectionConfig.h>
00029 #include "mutex.h"
00030
00031 #include <pcl_ros/point_cloud.h>
00032 #include <pcl/ros/conversions.h>
00033 #include <pcl/point_types.h>
00034 #include <pcl/impl/point_types.hpp>
00035
00036
00037 using namespace pcl;
00038 using namespace std;
00039
00040
00046 class HoleDetectionAlgorithm
00047 {
00048 protected:
00055 CMutex alg_mutex_;
00056
00057
00058 int hole_min_p;
00059 float box_y_end,box_z_ini,box_x,box_y_ini,box_z_end,Xl,Xc,Xr,Y;
00060 pcl::PointCloud<pcl::PointXYZRGB> cloud_in;
00061 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_for;
00062 public:
00069 typedef iri_hole_detection::HoleDetectionConfig Config;
00070
00077 Config config_;
00078
00087 HoleDetectionAlgorithm(void);
00088
00094 void lock(void) { alg_mutex_.enter(); };
00095
00101 void unlock(void) { alg_mutex_.exit(); };
00102
00110 bool try_enter(void) { return alg_mutex_.try_enter(); };
00111
00123 void config_update(Config& new_cfg, uint32_t level=0);
00124
00125
00126
00127
00134 ~HoleDetectionAlgorithm(void);
00135
00136 void cloud_all(int hole_min_p, float box_y_end, float box_z_ini,
00137 float box_x, float box_y_ini, float box_z_end,
00138 float Xl, float Xc, float Xr, float Y,
00139 pcl::PointCloud<pcl::PointXYZRGB>& cloud_in,
00140 pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud_out);
00141
00142 };
00143
00144 #endif