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
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #ifndef PCL_RECOGNITION_LINEMOD_LINE_RGBD
00039 #define PCL_RECOGNITION_LINEMOD_LINE_RGBD
00040
00041 #include <pcl/recognition/linemod.h>
00042 #include <pcl/recognition/color_gradient_modality.h>
00043 #include <pcl/recognition/surface_normal_modality.h>
00044 #include <pcl/io/tar.h>
00045
00046 namespace pcl
00047 {
00048
00049 struct BoundingBoxXYZ
00050 {
00052 BoundingBoxXYZ () : x (0.0f), y (0.0f), z (0.0f), width (0.0f), height (0.0f), depth (0.0f) {}
00053
00055 float x;
00057 float y;
00059 float z;
00060
00062 float width;
00064 float height;
00066 float depth;
00067 };
00068
00072 template <typename PointXYZT, typename PointRGBT=PointXYZT>
00073 class PCL_EXPORTS LineRGBD
00074 {
00075 public:
00076
00078 struct Detection
00079 {
00081 Detection () : template_id (0), object_id (0), detection_id (0), response (0.0f), bounding_box () {}
00082
00084 size_t template_id;
00086 size_t object_id;
00088 size_t detection_id;
00090 float response;
00092 BoundingBoxXYZ bounding_box;
00094 RegionXY region;
00095 };
00096
00098 LineRGBD ()
00099 : intersection_volume_threshold_ (1.0f)
00100 , linemod_ ()
00101 , color_gradient_mod_ ()
00102 , surface_normal_mod_ ()
00103 , cloud_xyz_ ()
00104 , cloud_rgb_ ()
00105 , template_point_clouds_ ()
00106 , bounding_boxes_ ()
00107 , object_ids_ ()
00108 , detections_ ()
00109 {
00110 }
00111
00113 virtual ~LineRGBD ()
00114 {
00115 }
00116
00127 bool
00128 loadTemplates (const std::string &file_name, size_t object_id = 0);
00129
00130 bool
00131 addTemplate (const SparseQuantizedMultiModTemplate & sqmmt, pcl::PointCloud<pcl::PointXYZRGBA> & cloud, size_t object_id = 0);
00132
00136 inline void
00137 setDetectionThreshold (float threshold)
00138 {
00139 linemod_.setDetectionThreshold (threshold);
00140 }
00141
00146 inline void
00147 setGradientMagnitudeThreshold (const float threshold)
00148 {
00149 color_gradient_mod_.setGradientMagnitudeThreshold (threshold);
00150 }
00151
00159 inline void
00160 setIntersectionVolumeThreshold (const float threshold = 1.0f)
00161 {
00162 intersection_volume_threshold_ = threshold;
00163 }
00164
00168 inline void
00169 setInputCloud (const typename pcl::PointCloud<PointXYZT>::ConstPtr & cloud)
00170 {
00171 cloud_xyz_ = cloud;
00172
00173 surface_normal_mod_.setInputCloud (cloud);
00174 surface_normal_mod_.processInputData ();
00175 }
00176
00180 inline void
00181 setInputColors (const typename pcl::PointCloud<PointRGBT>::ConstPtr & cloud)
00182 {
00183 cloud_rgb_ = cloud;
00184
00185 color_gradient_mod_.setInputCloud (cloud);
00186 color_gradient_mod_.processInputData ();
00187 }
00188
00194 int
00195 createAndAddTemplate (
00196 pcl::PointCloud<pcl::PointXYZRGBA> & cloud,
00197 const size_t object_id,
00198 const MaskMap & mask_xyz,
00199 const MaskMap & mask_rgb,
00200 const RegionXY & region);
00201
00202
00206 void
00207 detect (std::vector<typename pcl::LineRGBD<PointXYZT, PointRGBT>::Detection> & detections);
00208
00212 void
00213 detectSemiScaleInvariant (std::vector<typename pcl::LineRGBD<PointXYZT, PointRGBT>::Detection> & detections,
00214 float min_scale = 0.6944444f,
00215 float max_scale = 1.44f,
00216 float scale_multiplier = 1.2f);
00217
00224 void
00225 computeTransformedTemplatePoints (const size_t detection_id,
00226 pcl::PointCloud<pcl::PointXYZRGBA> & cloud);
00227
00232 inline std::vector<size_t>
00233 findObjectPointIndices (const size_t detection_id)
00234 {
00235 if (detection_id >= detections_.size ())
00236 PCL_ERROR ("ERROR pcl::LineRGBD::computeTransformedTemplatePoints - detection_id is out of bounds\n");
00237
00238
00239
00240 std::vector<size_t> vec;
00241 return (vec);
00242 }
00243
00244
00245 protected:
00246
00251 inline std::vector<size_t>
00252 alignTemplatePoints (const size_t detection_id)
00253 {
00254 if (detection_id >= detections_.size ())
00255 PCL_ERROR ("ERROR pcl::LineRGBD::computeTransformedTemplatePoints - detection_id is out of bounds\n");
00256
00257
00258
00259 std::vector<size_t> vec;
00260 return (vec);
00261 }
00262
00264 void
00265 refineDetectionsAlongDepth ();
00266
00268 void
00269 applyProjectiveDepthICPOnDetections ();
00270
00272 void
00273 removeOverlappingDetections ();
00274
00279 static float
00280 computeBoundingBoxIntersectionVolume (const BoundingBoxXYZ &box1, const BoundingBoxXYZ &box2);
00281
00282 private:
00284 bool
00285 readLTMHeader (int fd, pcl::io::TARHeader &header);
00286
00288 float intersection_volume_threshold_;
00289
00291 public: pcl::LINEMOD linemod_;
00293 pcl::ColorGradientModality<PointRGBT> color_gradient_mod_;
00295 pcl::SurfaceNormalModality<PointXYZT> surface_normal_mod_;
00296
00298 typename pcl::PointCloud<PointXYZT>::ConstPtr cloud_xyz_;
00300 typename pcl::PointCloud<PointRGBT>::ConstPtr cloud_rgb_;
00301
00303 pcl::PointCloud<pcl::PointXYZRGBA>::CloudVectorType template_point_clouds_;
00305 std::vector<pcl::BoundingBoxXYZ> bounding_boxes_;
00307 std::vector<size_t> object_ids_;
00308
00310 std::vector<typename pcl::LineRGBD<PointXYZT, PointRGBT>::Detection> detections_;
00311 };
00312
00313 }
00314
00315 #include <pcl/recognition/impl/linemod/line_rgbd.hpp>
00316
00317 #endif