Point Cloud Library (PCL)  1.14.1-dev
line_rgbd.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010-2011, Willow Garage, Inc.
6  *
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of Willow Garage, Inc. nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  */
37 
38 #pragma once
39 
40 #include <pcl/recognition/linemod.h>
41 #include <pcl/recognition/color_gradient_modality.h>
42 #include <pcl/recognition/surface_normal_modality.h>
43 #include <pcl/io/tar.h>
44 
45 namespace pcl
46 {
47 
49  {
50  /** \brief Constructor. */
51  BoundingBoxXYZ () = default;
52 
53  /** \brief X-coordinate of the upper left front point */
54  float x{0.0f};
55  /** \brief Y-coordinate of the upper left front point */
56  float y{0.0f};
57  /** \brief Z-coordinate of the upper left front point */
58  float z{0.0f};
59 
60  /** \brief Width of the bounding box */
61  float width{0.0f};
62  /** \brief Height of the bounding box */
63  float height{0.0f};
64  /** \brief Depth of the bounding box */
65  float depth{0.0f};
66  };
67 
68  /** \brief High-level class for template matching using the LINEMOD approach based on RGB and Depth data.
69  * \author Stefan Holzer
70  */
71  template <typename PointXYZT, typename PointRGBT=PointXYZT>
73  {
74  public:
75 
76  /** \brief A LineRGBD detection. */
77  struct Detection
78  {
79  /** \brief Constructor. */
80  Detection () = default;
81 
82  /** \brief The ID of the template. */
83  std::size_t template_id{0};
84  /** \brief The ID of the object corresponding to the template. */
85  std::size_t object_id{0};
86  /** \brief The ID of this detection. This is only valid for the last call of the method detect (...). */
87  std::size_t detection_id{0};
88  /** \brief The response of this detection. Responses are between 0 and 1, where 1 is best. */
89  float response{0.0f};
90  /** \brief The 3D bounding box of the detection. */
92  /** \brief The 2D template region of the detection. */
94  };
95 
96  /** \brief Constructor */
98  : color_gradient_mod_ ()
99  , surface_normal_mod_ ()
100  , cloud_xyz_ ()
101  , cloud_rgb_ ()
102  , detections_ ()
103  {
104  }
105 
106  /** \brief Destructor */
107  virtual ~LineRGBD () = default;
108 
109  /** \brief Loads templates from a LMT (LineMod Template) file. Overrides old templates.
110  *
111  * LineMod Template files are TAR files that store pairs of PCD datasets
112  * together with their LINEMOD signatures in \ref
113  * SparseQuantizedMultiModTemplate format.
114  *
115  * \param[in] file_name The name of the file that stores the templates.
116  * \param object_id
117  *
118  * \return true, if the operation was successful, false otherwise.
119  */
120  bool
121  loadTemplates (const std::string &file_name, std::size_t object_id = 0);
122 
123  bool
124  addTemplate (const SparseQuantizedMultiModTemplate & sqmmt, pcl::PointCloud<pcl::PointXYZRGBA> & cloud, std::size_t object_id = 0);
125 
126  /** \brief Sets the threshold for the detection responses. Responses are between 0 and 1, where 1 is a best.
127  * \param[in] threshold The threshold used to decide where a template is detected.
128  */
129  inline void
130  setDetectionThreshold (float threshold)
131  {
132  linemod_.setDetectionThreshold (threshold);
133  }
134 
135  /** \brief Sets the threshold on the magnitude of color gradients. Color gradients with a magnitude below
136  * this threshold are not considered in the detection process.
137  * \param[in] threshold The threshold on the magnitude of color gradients.
138  */
139  inline void
140  setGradientMagnitudeThreshold (const float threshold)
141  {
142  color_gradient_mod_.setGradientMagnitudeThreshold (threshold);
143  }
144 
145  /** \brief Sets the threshold for the decision whether two detections of the same template are merged or not.
146  * If ratio between the intersection of the bounding boxes of two detections and the original bounding
147  * boxes is larger than the specified threshold then they are merged. If detection A overlaps with
148  * detection B and B with C than A, B, and C are merged. Threshold has to be between 0 and 1.
149  * \param[in] threshold The threshold on the ratio between the intersection bounding box and the original
150  * bounding box.
151  */
152  inline void
153  setIntersectionVolumeThreshold (const float threshold = 1.0f)
154  {
155  intersection_volume_threshold_ = threshold;
156  }
157 
158  /** \brief Sets the input cloud with xyz point coordinates. The cloud has to be organized.
159  * \param[in] cloud The input cloud with xyz point coordinates.
160  */
161  inline void
163  {
164  cloud_xyz_ = cloud;
165 
166  surface_normal_mod_.setInputCloud (cloud);
167  surface_normal_mod_.processInputData ();
168  }
169 
170  /** \brief Sets the input cloud with rgb values. The cloud has to be organized.
171  * \param[in] cloud The input cloud with rgb values.
172  */
173  inline void
175  {
176  cloud_rgb_ = cloud;
177 
178  color_gradient_mod_.setInputCloud (cloud);
179  color_gradient_mod_.processInputData ();
180  }
181 
182  /** \brief Creates a template from the specified data and adds it to the matching queue.
183  * \param cloud
184  * \param object_id
185  * \param[in] mask_xyz the mask that determine which parts of the xyz-modality are used for creating the template.
186  * \param[in] mask_rgb the mask that determine which parts of the rgb-modality are used for creating the template.
187  * \param[in] region the region which will be associated with the template (can be larger than the actual modality-maps).
188  */
189  int
190  createAndAddTemplate (
192  const std::size_t object_id,
193  const MaskMap & mask_xyz,
194  const MaskMap & mask_rgb,
195  const RegionXY & region);
196 
197 
198  /** \brief Applies the detection process and fills the supplied vector with the detection instances.
199  * \param[out] detections The storage for the detection instances.
200  */
201  void
202  detect (std::vector<typename pcl::LineRGBD<PointXYZT, PointRGBT>::Detection> & detections);
203 
204  /** \brief Applies the detection process in a semi-scale-invariant manner. This is done by actually
205  * scaling the template to different sizes.
206  */
207  void
208  detectSemiScaleInvariant (std::vector<typename pcl::LineRGBD<PointXYZT, PointRGBT>::Detection> & detections,
209  float min_scale = 0.6944444f,
210  float max_scale = 1.44f,
211  float scale_multiplier = 1.2f);
212 
213  /** \brief Computes and returns the point cloud of the specified detection. This is the template point
214  * cloud transformed to the detection coordinates. The detection ID refers to the last call of
215  * the method detect (...).
216  * \param[in] detection_id The ID of the detection (according to the last call of the method detect (...)).
217  * \param[out] cloud The storage for the transformed points.
218  */
219  void
220  computeTransformedTemplatePoints (const std::size_t detection_id,
222 
223  /** \brief Finds the indices of the points in the input cloud which correspond to the specified detection.
224  * The detection ID refers to the last call of the method detect (...).
225  * \param[in] detection_id The ID of the detection (according to the last call of the method detect (...)).
226  */
227  inline std::vector<std::size_t>
228  findObjectPointIndices (const std::size_t detection_id)
229  {
230  if (detection_id >= detections_.size ())
231  PCL_ERROR ("ERROR pcl::LineRGBD::computeTransformedTemplatePoints - detection_id is out of bounds\n");
232 
233  // TODO: compute transform from detection
234  // TODO: transform template points
235  std::vector<std::size_t> vec;
236  return (vec);
237  }
238 
239 
240  protected:
241 
242  /** \brief Aligns the template points with the points found at the detection position of the specified detection.
243  * The detection ID refers to the last call of the method detect (...).
244  * \param[in] detection_id The ID of the detection (according to the last call of the method detect (...)).
245  */
246  inline std::vector<std::size_t>
247  alignTemplatePoints (const std::size_t detection_id)
248  {
249  if (detection_id >= detections_.size ())
250  PCL_ERROR ("ERROR pcl::LineRGBD::computeTransformedTemplatePoints - detection_id is out of bounds\n");
251 
252  // TODO: compute transform from detection
253  // TODO: transform template points
254  std::vector<std::size_t> vec;
255  return (vec);
256  }
257 
258  /** \brief Refines the found detections along the depth. */
259  void
260  refineDetectionsAlongDepth ();
261 
262  /** \brief Applies projective ICP on detections to find their correct position in depth. */
263  void
264  applyProjectiveDepthICPOnDetections ();
265 
266  /** \brief Checks for overlapping detections, removes them and keeps only the strongest one. */
267  void
268  removeOverlappingDetections ();
269 
270  /** \brief Computes the volume of the intersection between two bounding boxes.
271  * \param[in] box1 First bounding box.
272  * \param[in] box2 Second bounding box.
273  */
274  static float
275  computeBoundingBoxIntersectionVolume (const BoundingBoxXYZ &box1, const BoundingBoxXYZ &box2);
276 
277  private:
278  /** \brief Read another LTM header chunk. */
279  bool
280  readLTMHeader (int fd, pcl::io::TARHeader &header);
281 
282  /** \brief Intersection volume threshold. */
283  float intersection_volume_threshold_{1.0f};
284 
285  /** \brief LINEMOD instance. */
287  /** \brief Color gradient modality. */
289  /** \brief Surface normal modality. */
291 
292  /** \brief XYZ point cloud. */
294  /** \brief RGB point cloud. */
296 
297  /** \brief Point clouds corresponding to the templates. */
299  /** \brief Bounding boxes corresponding to the templates. */
300  std::vector<pcl::BoundingBoxXYZ> bounding_boxes_;
301  /** \brief Object IDs corresponding to the templates. */
302  std::vector<std::size_t> object_ids_;
303 
304  /** \brief Detections from last call of method detect (...). */
305  std::vector<typename pcl::LineRGBD<PointXYZT, PointRGBT>::Detection> detections_;
306  };
307 
308 }
309 
310 #include <pcl/recognition/impl/linemod/line_rgbd.hpp>
Modality based on max-RGB gradients.
Template matching using the LINEMOD approach.
Definition: linemod.h:327
High-level class for template matching using the LINEMOD approach based on RGB and Depth data.
Definition: line_rgbd.h:73
void setDetectionThreshold(float threshold)
Sets the threshold for the detection responses.
Definition: line_rgbd.h:130
pcl::PointCloud< PointXYZT >::ConstPtr cloud_xyz_
XYZ point cloud.
Definition: line_rgbd.h:293
pcl::LINEMOD linemod_
LINEMOD instance.
Definition: line_rgbd.h:286
pcl::PointCloud< PointRGBT >::ConstPtr cloud_rgb_
RGB point cloud.
Definition: line_rgbd.h:295
std::vector< typename pcl::LineRGBD< PointXYZT, PointRGBT >::Detection > detections_
Detections from last call of method detect (...).
Definition: line_rgbd.h:305
void setGradientMagnitudeThreshold(const float threshold)
Sets the threshold on the magnitude of color gradients.
Definition: line_rgbd.h:140
std::vector< std::size_t > findObjectPointIndices(const std::size_t detection_id)
Finds the indices of the points in the input cloud which correspond to the specified detection.
Definition: line_rgbd.h:228
std::vector< pcl::BoundingBoxXYZ > bounding_boxes_
Bounding boxes corresponding to the templates.
Definition: line_rgbd.h:300
std::vector< std::size_t > object_ids_
Object IDs corresponding to the templates.
Definition: line_rgbd.h:302
pcl::ColorGradientModality< PointRGBT > color_gradient_mod_
Color gradient modality.
Definition: line_rgbd.h:288
pcl::SurfaceNormalModality< PointXYZT > surface_normal_mod_
Surface normal modality.
Definition: line_rgbd.h:290
std::vector< std::size_t > alignTemplatePoints(const std::size_t detection_id)
Aligns the template points with the points found at the detection position of the specified detection...
Definition: line_rgbd.h:247
virtual ~LineRGBD()=default
Destructor.
pcl::PointCloud< pcl::PointXYZRGBA >::CloudVectorType template_point_clouds_
Point clouds corresponding to the templates.
Definition: line_rgbd.h:298
void setIntersectionVolumeThreshold(const float threshold=1.0f)
Sets the threshold for the decision whether two detections of the same template are merged or not.
Definition: line_rgbd.h:153
void setInputColors(const typename pcl::PointCloud< PointRGBT >::ConstPtr &cloud)
Sets the input cloud with rgb values.
Definition: line_rgbd.h:174
void setInputCloud(const typename pcl::PointCloud< PointXYZT >::ConstPtr &cloud)
Sets the input cloud with xyz point coordinates.
Definition: line_rgbd.h:162
LineRGBD()
Constructor.
Definition: line_rgbd.h:97
std::vector< PointCloud< PointT >, Eigen::aligned_allocator< PointCloud< PointT > > > CloudVectorType
Definition: point_cloud.h:412
shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:414
#define PCL_EXPORTS
Definition: pcl_macros.h:323
float width
Width of the bounding box.
Definition: line_rgbd.h:61
float x
X-coordinate of the upper left front point.
Definition: line_rgbd.h:54
float y
Y-coordinate of the upper left front point.
Definition: line_rgbd.h:56
float depth
Depth of the bounding box.
Definition: line_rgbd.h:65
float z
Z-coordinate of the upper left front point.
Definition: line_rgbd.h:58
BoundingBoxXYZ()=default
Constructor.
float height
Height of the bounding box.
Definition: line_rgbd.h:63
A LineRGBD detection.
Definition: line_rgbd.h:78
BoundingBoxXYZ bounding_box
The 3D bounding box of the detection.
Definition: line_rgbd.h:91
Detection()=default
Constructor.
RegionXY region
The 2D template region of the detection.
Definition: line_rgbd.h:93
Defines a region in XY-space.
Definition: region_xy.h:82
A multi-modality template constructed from a set of quantized multi-modality features.
A TAR file's header, as described on https://en.wikipedia.org/wiki/Tar_%28file_format%29.
Definition: tar.h:50