class_pinhole_projection.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
35 #ifndef _CLASS_PINHOLE_PROJECTION_CPP_
36 #define _CLASS_PINHOLE_PROJECTION_CPP_
37 
39 
40 
41 
42 
47 int class_pinhole_projection::set_projection_plane(double a, double b, double c, double d)
48 {
49  projection_plane.a = a;
50  projection_plane.b = b;
51  projection_plane.c = c;
52  projection_plane.d = d;
53  return 1;}
54 
60 int class_pinhole_projection::print_CvMat(cv::Mat *mat, const char* name)
61 {
62 
63  if (name==NULL)
64  {
65  printf("cvMat has %d cols and %d lines\n", mat->cols, mat->rows);
66  }
67  else
68  {
69  printf("%s has %d cols and %d lines\n",name, mat->cols, mat->rows);
70  }
71 
72  for (int l=0; l<mat->rows; l++)
73  {
74  printf("[");
75  for (int c=0; c<mat->cols; c++)
76  {
77  printf("%3.2f ", mat->at<double>(l,c));
78  }
79  printf("]\n");
80  }
81 
82  return 1;}
83 
84 int class_pinhole_projection::project_vertex_to_pixel(const pcl::PointCloud<pcl::PointXYZ>::Ptr v, std::vector<pcl::PointXY>* p)
85 {
86 
87  cv::Mat vertexes(4, (int)v->points.size(), CV_64FC1);
88  cv::Mat pixels(3, (int)v->points.size(), CV_64FC1);
89 
90 
91  for (size_t i=0; i < v->points.size(); i++) //set the vertexes homogeneous matrix
92  {
93  vertexes.at<double>(0,i) = v->points.at(i).x;
94  vertexes.at<double>(1,i) = v->points.at(i).y;
95  vertexes.at<double>(2,i) = v->points.at(i).z;
96  vertexes.at<double>(3,i) = 1;
97  }
98 
99 
100  cv::Mat transformation;
101  transformation.create(4,4,CV_64F);
102  transformation = intrinsic*extrinsic;
103 
104 
105  //compute the pixel coordinates
106  pixels = transformation*vertexes;
107 
108 
109  //erase all elements of p
110  p->erase(p->begin(), p->end());
111 
112 
113 
114  for (int i=0; i < pixels.cols; i++) //set output vector
115  {
116  pcl::PointXY pt;
117  pt.x = (pixels.at<double>(0,i) / pixels.at<double>(2,i));
118  pt.y = (pixels.at<double>(1,i) / pixels.at<double>(2,i));
119  p->push_back(pt);
120 
121  //printf("mat 0 = %f, mat 1 = %f mat2 = %f\n",pixels.at<double>(0,i), pixels.at<double>(1,i), pixels.at<double>(2,i));
122  //printf("i=%d X=%3.2f Y=%3.2f Z=%3.2f --> pix x=%f y=%f\n",
123  //i,
124  //v->points[i].x,
125  //v->points[i].y,
126  //v->points[i].z,
127  //p->at(i).x,
128  //p->at(i).y
129  //);
130 
131 
132 
133  }
134 
135 
136  //printf("p->size()=%d\n",(int) p->size());
137  //for (int i=1; i<(int)p->size(); i++)
138  //{
139  //printf("i=%d X=%3.2f Y=%3.2f Z=%3.2f --> pix x=%f y=%f\n",
140  //i,
141  //v->points[i].x,
142  //v->points[i].y,
143  //v->points[i].z,
144  //p->at(i).x,
145  //p->at(i).y
146  //);
147  //}
148 
149 
150  return 1;}
151 
152 
153 int class_pinhole_projection::project_pixel_with_color_to_vertex(const pcl::PointCloud<pcl::PointXYZRGB>* p, pcl::PointCloud<pcl::PointXYZRGB>* v)
154 {
155  cv::Mat transformation;
156  transformation.create(4,4,CV_64F);
157  transformation = intrinsic*extrinsic;
158 
159  cv::Mat* M = &transformation;
160  int valid_projections=0;
161 
162  //set variables to the transformation matrix
163  double p11 = M->at<double>(0,0); double p12 = M->at<double>(0,1); double p13 = M->at<double>(0,2); double p14 = M->at<double>(0,3);
164  double p21 = M->at<double>(1,0); double p22 = M->at<double>(1,1); double p23 = M->at<double>(1,2); double p24 = M->at<double>(1,3);
165  double p31 = M->at<double>(2,0); double p32 = M->at<double>(2,1); double p33 = M->at<double>(2,2); double p34 = M->at<double>(2,3);
166 
167  //set references to the plane parameters
168  double &A = projection_plane.a; double &B = projection_plane.b; double &C = projection_plane.c; double &D = projection_plane.d;
169 
170  //compute constants
171  double K1 = (C*p12*p34+p13*D*p32-p12*p33*D-p32*C*p14-p13*B*p34+p33*B*p14);
172  double K2 = (p32*C*p24-p34*C*p22-p33*B*p24-p32*p23*D+p33*D*p22+p34*p23*B);
173  double K3 = (-p13*D*p22+C*p14*p22-C*p12*p24+p12*p23*D-p14*p23*B+p13*B*p24);
174  double K4 = (C*p31*p12+p11*p33*B+p13*A*p32-C*p11*p32-p33*A*p12-p31*p13*B);
175  double K5 = (C*p21*p32+p31*p23*B+p33*A*p22-C*p31*p22-p23*A*p32-p21*p33*B);
176  double K6 = (-C*p21*p12-p11*p23*B+C*p11*p22+p23*A*p12+p21*p13*B-p13*A*p22);
177  double K7 = (p11*p34*C-p13*A*p34-p11*p33*D+p33*A*p14+p31*p13*D-p31*C*p14);
178  double K8 = (-p33*A*p24-p31*p23*D+p23*A*p34+p21*p33*D-C*p21*p34+C*p31*p24);
179  double K9 = (C*p21*p14+p13*A*p24-p23*A*p14-p21*p13*D+p11*p23*D-C*p11*p24);
180  double K10 = (C*p31*p12+p11*p33*B+p13*A*p32-C*p11*p32-p33*A*p12-p31*p13*B);
181  double K11 = (C*p21*p32+p31*p23*B+p33*A*p22-C*p31*p22-p23*A*p32-p21*p33*B);
182  double K12 = (-C*p21*p12-p11*p23*B+C*p11*p22+p23*A*p12+p21*p13*B-p13*A*p22);
183 
184  //empty all points from cloud
185  v->points.erase(v->points.begin(), v->points.end());
186 
187  //Create the cv::Mat for valid projection assesment
188  cv::Mat XYZ_plane(4, 1, CV_64FC1);
189  XYZ_plane.at<double>(3,0) = 1; //homogeneous coordinates
190  cv::Mat XYZ_image(4, 1, CV_64FC1);
191 
192  //Begin projection of pixels
193  for (int i=0; i<(int)p->points.size();i++)
194  {
195  pcl::PointXYZRGB pix = p->at(i);
196  pcl::PointXYZRGB pt;
197  pt.x = -(K1*pix.y + K2*pix.x + K3) / (K4*pix.y + K5*pix.x + K6);
198  pt.y = (K7*pix.y + K8*pix.x + K9) / (K10*pix.y + K11*pix.x + K12);
199  pt.z = -(A*pt.x + B*pt.y + D)/C;
200 
201  //Check is projection is valid
202  XYZ_plane.at<double>(0,0) = pt.x;
203  XYZ_plane.at<double>(1,0) = pt.y;
204  XYZ_plane.at<double>(2,0) = pt.z;
205  XYZ_image = extrinsic*XYZ_plane;
206 
207  if (XYZ_image.at<double>(2,0)>0) //if its valid project
208  {
209  valid_projections++;
210  pt.rgb = pix.rgb;
211  v->points.push_back(pt);
212  }
213  else
214  {
215  pt.x = NAN;
216  pt.y = NAN;
217  pt.z = NAN;
218  pt.rgb = NAN;
219  v->points.push_back(pt);
220  }
221  }
222 
223  if (0) //Debug
224  {
225  ROS_INFO("Projecting %d pixels. Valid projections = %d", (int)p->size(), valid_projections);
226  }
227 return valid_projections;};
228 
229 int class_pinhole_projection::project_pixel_to_vertex(const std::vector<pcl::PointXY>* p, pcl::PointCloud<pcl::PointXYZ>* v)
230 {
231  cv::Mat transformation;
232  transformation.create(4,4,CV_64F);
233  transformation = intrinsic*extrinsic;
234 
235  cv::Mat* M = &transformation;
236  int valid_projections=0;
237 
238  //set variables to the transformation matrix
239  double p11 = M->at<double>(0,0); double p12 = M->at<double>(0,1); double p13 = M->at<double>(0,2); double p14 = M->at<double>(0,3);
240  double p21 = M->at<double>(1,0); double p22 = M->at<double>(1,1); double p23 = M->at<double>(1,2); double p24 = M->at<double>(1,3);
241  double p31 = M->at<double>(2,0); double p32 = M->at<double>(2,1); double p33 = M->at<double>(2,2); double p34 = M->at<double>(2,3);
242 
243  //set references to the plane parameters
244  double &A = projection_plane.a; double &B = projection_plane.b; double &C = projection_plane.c; double &D = projection_plane.d;
245 
246  //compute constants
247  double K1 = (C*p12*p34+p13*D*p32-p12*p33*D-p32*C*p14-p13*B*p34+p33*B*p14);
248  double K2 = (p32*C*p24-p34*C*p22-p33*B*p24-p32*p23*D+p33*D*p22+p34*p23*B);
249  double K3 = (-p13*D*p22+C*p14*p22-C*p12*p24+p12*p23*D-p14*p23*B+p13*B*p24);
250  double K4 = (C*p31*p12+p11*p33*B+p13*A*p32-C*p11*p32-p33*A*p12-p31*p13*B);
251  double K5 = (C*p21*p32+p31*p23*B+p33*A*p22-C*p31*p22-p23*A*p32-p21*p33*B);
252  double K6 = (-C*p21*p12-p11*p23*B+C*p11*p22+p23*A*p12+p21*p13*B-p13*A*p22);
253  double K7 = (p11*p34*C-p13*A*p34-p11*p33*D+p33*A*p14+p31*p13*D-p31*C*p14);
254  double K8 = (-p33*A*p24-p31*p23*D+p23*A*p34+p21*p33*D-C*p21*p34+C*p31*p24);
255  double K9 = (C*p21*p14+p13*A*p24-p23*A*p14-p21*p13*D+p11*p23*D-C*p11*p24);
256  double K10 = (C*p31*p12+p11*p33*B+p13*A*p32-C*p11*p32-p33*A*p12-p31*p13*B);
257  double K11 = (C*p21*p32+p31*p23*B+p33*A*p22-C*p31*p22-p23*A*p32-p21*p33*B);
258  double K12 = (-C*p21*p12-p11*p23*B+C*p11*p22+p23*A*p12+p21*p13*B-p13*A*p22);
259 
260  //empty all points from cloud
261  v->points.erase(v->points.begin(), v->points.end());
262 
263  //Create the cv::Mat for valid projection assesment
264  cv::Mat XYZ_plane(4, 1, CV_64FC1);
265  XYZ_plane.at<double>(3,0) = 1; //homogeneous coordinates
266  cv::Mat XYZ_image(4, 1, CV_64FC1);
267 
268  //Begin projection of pixels
269  for (int i=0; i<(int)p->size();i++)
270  {
271  pcl::PointXY pix = p->at(i);
272  pcl::PointXYZ pt;
273  pt.x = -(K1*pix.y + K2*pix.x + K3) / (K4*pix.y + K5*pix.x + K6);
274  pt.y = (K7*pix.y + K8*pix.x + K9) / (K10*pix.y + K11*pix.x + K12);
275  pt.z = -(A*pt.x + B*pt.y + D)/C;
276 
277  //Check is projection is valid
278  XYZ_plane.at<double>(0,0) = pt.x;
279  XYZ_plane.at<double>(1,0) = pt.y;
280  XYZ_plane.at<double>(2,0) = pt.z;
281  XYZ_image = extrinsic*XYZ_plane;
282 
283  if (XYZ_image.at<double>(2,0)>0) //if its valid project
284  {
285  valid_projections++;
286  v->points.push_back(pt);
287  }
288  else
289  {
290  pt.x = NAN;
291  pt.y = NAN;
292  pt.z = NAN;
293  v->points.push_back(pt);
294  }
295  }
296 
297  if (0) //Debug
298  {
299  ROS_INFO("Projecting %d pixels. Valid projections = %d", (int)p->size(), valid_projections);
300  }
301 
302 return valid_projections;}
303 
304 #endif
305 
struct class_pinhole_projection::@1 projection_plane
CGAL::Cartesian< double > K1
Definition: preh.h:105
int project_pixel_to_vertex(const std::vector< pcl::PointXY > *p, pcl::PointCloud< pcl::PointXYZ > *v)
int set_projection_plane(double a, double b, double c, double d)
Sets and gets.
int project_pixel_with_color_to_vertex(const pcl::PointCloud< pcl::PointXYZRGB > *p, pcl::PointCloud< pcl::PointXYZRGB > *v)
header for pinhole projection. Defines default distortions parameters for mit dataset cameras...
int project_vertex_to_pixel(const pcl::PointCloud< pcl::PointXYZ >::Ptr v, std::vector< pcl::PointXY > *p)
Projections.
unsigned char b[16]
int print_CvMat(cv::Mat *mat, const char *name)
Prints.


polygon_primitives_extraction
Author(s): Miguel Oliveira
autogenerated on Mon Mar 2 2015 01:32:42