frame_projector.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2013, Alex Teichman and Stephen Miller (Stanford University)
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the <organization> nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 
27 RTAB-Map integration: Mathieu Labbe
28 */
29 
33 #include <rtabmap/core/util3d.h>
34 #include <opencv2/highgui/highgui.hpp>
35 #include <opencv2/imgproc/imgproc.hpp>
36 
37 using namespace std;
38 using namespace Eigen;
39 
40 namespace clams
41 {
42  FrameProjector::FrameProjector(const rtabmap::CameraModel & model) :
43  model_(model)
44  {
46  }
47 
48  // pcd is in /map frame
49  FrameProjector::RangeIndex FrameProjector::cloudToRangeIndex(const pcl::PointCloud<pcl::PointXYZ>::Ptr & pcd) const
50  {
51  int height = model_.imageHeight();
52  int width = model_.imageWidth();
53  RangeIndex ind;
54  if((int)ind.size() != height)
55  ind.resize(height);
56  for(size_t y = 0; y < ind.size(); ++y)
57  if((int)ind[y].size() != width)
58  ind[y].resize(width);
59  for(size_t y = 0; y < ind.size(); ++y) {
60  for(size_t x = 0; x < ind[y].size(); ++x) {
61  ind[y][x].clear();
62  ind[y][x].reserve(10);
63  }
64  }
65 
67 
68  ProjectivePoint ppt;
69  for(size_t i = 0; i < pcd->size(); ++i) {
70  if(!isFinite(pcd->at(i)))
71  continue;
72  ppt = reproject(rtabmap::util3d::transformPoint(pcd->at(i), t));
73  if(ppt.z_ == 0 || !(ppt.u_ >= 0 && ppt.v_ >= 0 && ppt.u_ < width && ppt.v_ < height))
74  continue;
75  ind[ppt.v_][ppt.u_].push_back(ppt.z_);
76  }
77  return ind;
78  }
79 
80  pcl::PointXYZ FrameProjector::project(const ProjectivePoint& ppt) const
81  {
82  UASSERT(ppt.u_ >= 0 && ppt.v_ >= 0 && ppt.u_ < model_.imageWidth() && ppt.v_ < model_.imageHeight());
83 
84  pcl::PointXYZ pt;
85 
86  model_.project(ppt.u_, ppt.v_, ppt.z_, pt.x, pt.y, pt.z);
87  return pt;
88  }
89 
90  ProjectivePoint FrameProjector::reproject(const pcl::PointXYZ & pt) const
91  {
92  UASSERT(isFinite(pt));
93 
94  ProjectivePoint ppt;
95 
96  if(pt.z > 0)
97  {
98  model_.reproject(pt.x, pt.y, pt.z, ppt.u_, ppt.v_);
99  ppt.z_ = pt.z;
100  }
101 
102  return ppt;
103  }
104 
106  const pcl::PointCloud<pcl::PointXYZ>::Ptr & map,
107  const rtabmap::Transform & transform,
108  const cv::Mat& measurement,
109  double coneRadius,
110  double coneStdevThresh) const
111  {
112  cv::Mat estimate = cv::Mat::zeros(measurement.size(), CV_32FC1);
113 
114  // -- Get the depth index.
115  pcl::PointCloud<pcl::PointXYZ>::Ptr transformed = rtabmap::util3d::transformPointCloud(map, transform);
116  RangeIndex rindex = cloudToRangeIndex(transformed);
117 
118  // -- Compute the edge-of-map mask.
119  cv::Mat naive_mapframe = rtabmap::util3d::projectCloudToCamera(model_.imageSize(), model_.K(), transformed, model_.localTransform());
120  const cv::Mat& measurement_depth = measurement;
121  const cv::Mat& naive_mapdepth = naive_mapframe;
122  cv::Mat1b mask(measurement_depth.rows, measurement_depth.cols);
123  mask = 0;
124  for(int y = 0; y < mask.rows; ++y)
125  for(int x = 0; x < mask.cols; ++x)
126  if(naive_mapdepth.at<float>(y, x) != 0)
127  mask(y, x) = 255;
128 
129  cv::dilate(mask, mask, cv::Mat(), cv::Point(-1, -1), 4);
130  cv::erode(mask, mask, cv::Mat(), cv::Point(-1, -1), 15);
131 
132  bool isInMM = measurement_depth.type() == CV_16UC1;
133 
134  // -- Main loop: for all points in the image...
135  ProjectivePoint ppt;
136  for(ppt.v_ = 0; ppt.v_ < measurement_depth.rows; ++ppt.v_) {
137  for(ppt.u_ = 0; ppt.u_ < measurement_depth.cols; ++ppt.u_) {
138 
139  float value = isInMM?float(measurement_depth.at<unsigned short>(ppt.v_, ppt.u_))*0.001f:measurement_depth.at<float>(ppt.v_, ppt.u_);
140 
141  // -- Reject points with no data.
142  if(value == 0)
143  continue;
144  if(naive_mapdepth.at<float>(ppt.v_, ppt.u_) == 0)
145  continue;
146 
147  // -- Reject points on the edge of the map.
148  if(mask(ppt.v_, ppt.u_) == 0)
149  continue;
150 
151  // -- Find nearby points in the cone to get a good estimate of the map depth.
152  double mean = 0;
153  double stdev = 0;
154  //double stdev_thresh = numeric_limits<double>::max();
155  bool valid = coneFit(
156  naive_mapdepth.size(),
157  rindex,
158  ppt.u_,
159  ppt.v_,
160  coneRadius,
161  value,
162  &mean,
163  &stdev);
164  if(!valid)
165  continue;
166  if(stdev > coneStdevThresh)
167  continue;
168 
169  estimate.at<float>(ppt.v_, ppt.u_) = mean;
170  }
171  }
172  return estimate;
173  }
174 
175  bool FrameProjector::coneFit(const cv::Size& imageSize, const RangeIndex& rindex,
176  int uc, int vc, double radius, double measurement_depth,
177  double* mean, double* stdev) const
178  {
179  pcl::PointXYZ pt_center, pt_ul, pt_lr;
180  ProjectivePoint ppt, ppt_ul, ppt_lr;
181  ppt.u_ = uc;
182  ppt.v_ = vc;
183  ppt.z_ = measurement_depth;
184  pt_center = project(ppt);
185 
186  pt_ul = pt_center;
187  pt_lr = pt_center;
188  pt_ul.x -= radius;
189  pt_ul.y -= radius;
190  pt_lr.x += radius;
191  pt_lr.y += radius;
192 
193  if(!pcl::isFinite(pt_ul) || !pcl::isFinite(pt_lr))
194  {
195  return false;
196  }
197 
198  ppt_ul = reproject(pt_ul);
199  ppt_lr = reproject(pt_lr);
200  if(ppt_ul.z_ == 0 || !(ppt_ul.u_ >= 0 && ppt_ul.v_ >= 0 && ppt_ul.u_ < imageSize.width && ppt_ul.v_ < imageSize.height))
201  return false;
202  if(ppt_lr.z_ == 0 || !(ppt_lr.u_ >= 0 && ppt_lr.v_ >= 0 && ppt_lr.u_ < imageSize.width && ppt_lr.v_ < imageSize.height))
203  return false;
204 
205  int min_u = ppt_ul.u_;
206  int max_u = ppt_lr.u_;
207  int min_v = ppt_ul.v_;
208  int max_v = ppt_lr.v_;
209 
210  *mean = 0;
211  double num = 0;
212  for(ppt.u_ = min_u; ppt.u_ <= max_u; ++ppt.u_) {
213  for(ppt.v_ = min_v; ppt.v_ <= max_v; ++ppt.v_) {
214  const vector<double>& vals = rindex[ppt.v_][ppt.u_];
215  for(size_t i = 0; i < vals.size(); ++i) {
216  double mult = vals[i] / measurement_depth;
217  if(mult > MIN_MULT && mult < MAX_MULT) {
218  *mean += vals[i];
219  ++num;
220  }
221  }
222  }
223  }
224  if(num == 0)
225  return false;
226  *mean /= num;
227 
228  double var = 0;
229  for(ppt.u_ = min_u; ppt.u_ <= max_u; ++ppt.u_) {
230  for(ppt.v_ = min_v; ppt.v_ <= max_v; ++ppt.v_) {
231  const vector<double>& vals = rindex[ppt.v_][ppt.u_];
232  for(size_t i = 0; i < vals.size(); ++i) {
233  double mult = vals[i] / measurement_depth;
234  if(mult > MIN_MULT && mult < MAX_MULT)
235  var += (vals[i] - *mean) * (vals[i] - *mean);
236  }
237  }
238  }
239  var /= num;
240 
241  *stdev = sqrt(var);
242  return true;
243  }
244 
245 } // namespace clams
246 
GLM_FUNC_DECL genIType mask(genIType const &count)
bool RTABMAP_EXP isFinite(const cv::Point3f &pt)
Definition: util3d.cpp:3035
int imageWidth() const
Definition: CameraModel.h:113
pcl::PointXYZ project(const ProjectivePoint &ppt) const
const cv::Size & imageSize() const
Definition: CameraModel.h:112
cv::Point3f RTABMAP_EXP transformPoint(const cv::Point3f &pt, const Transform &transform)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP transformPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform)
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
double stdev(const Eigen::VectorXd &vec)
#define MAX_MULT
cv::Mat estimateMapDepth(const pcl::PointCloud< pcl::PointXYZ >::Ptr &map, const rtabmap::Transform &transform, const cv::Mat &measurement, double coneRadius=0.02, double coneStdevThresh=0.03) const
#define UASSERT(condition)
rtabmap::CameraModel model_
void reproject(float x, float y, float z, float &u, float &v) const
bool coneFit(const cv::Size &imageSize, const RangeIndex &rindex, int uc, int vc, double radius, double measurement_depth, double *mean, double *stdev) const
bool isValidForReprojection() const
Definition: CameraModel.h:81
#define MIN_MULT
void project(float u, float v, float depth, float &x, float &y, float &z) const
std::vector< std::vector< std::vector< double > > > RangeIndex
ULogger class and convenient macros.
RangeIndex cloudToRangeIndex(const pcl::PointCloud< pcl::PointXYZ >::Ptr &pcd) const
cv::Mat RTABMAP_EXP projectCloudToCamera(const cv::Size &imageSize, const cv::Mat &cameraMatrixK, const cv::Mat &laserScan, const rtabmap::Transform &cameraTransform)
Definition: util3d.cpp:2672
Transform inverse() const
Definition: Transform.cpp:169
cv::Mat K() const
Definition: CameraModel.h:103
ProjectivePoint reproject(const pcl::PointXYZ &pt) const
int imageHeight() const
Definition: CameraModel.h:114
const Transform & localTransform() const
Definition: CameraModel.h:109


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:31