camera_projection.h
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 ***************************************************************************************************/
36 #ifndef _CAMERA_PROJECTION_H_
37 #define _CAMERA_PROJECTION_H_
38 
39 #define PFLN {printf("DEBUG PRINT FILE %s LINE %d\n",__FILE__,__LINE__);}
40 
41 //####################################################################
44 #include <ros/ros.h>
45 
46 #include <opencv2/imgproc/imgproc.hpp>
47 #include <opencv2/highgui/highgui.hpp>
48 #include <opencv2/core/core.hpp>
49 
50 #include <sensor_msgs/PointCloud2.h>
51 #include <pcl/ros/conversions.h>
52 #include <pcl/point_cloud.h>
53 #include <pcl/point_types.h>
54 #include <pcl_ros/point_cloud.h>
55 #include <tf/tf.h>
56 
57 //include
59 #include "polygon_intersection.h"
60 #include <bo_polygon2d/polygon_boolean_operations.h>
61 #include "distortion_correction.h"
62 #include "projection_mesh.h"
63 
64 typedef cv::Vec<unsigned char, 3> t_pixel;
65 
69 class class_camera_projection: public class_pinhole_projection, public class_distortion_correction, public class_polygon_boolean_operations, virtual public class_camera_parameters, public class_projection_mesh
70 {
71  // ------------------------------------------------------------------------------
72  //PUBLIC SECTION OF THE CLASS
73  // ------------------------------------------------------------------------------
74  public:
75 
80 
85 
95  int set_image(const cv::Mat* image, ros::Time time, std::string name="none");
96 
105  int create_image_canvas(const cv::Mat* image, std::vector<pcl::PointXY>* pts);
106  int create_image_canvas_for_known_camera(const cv::Mat* image, std::vector<pcl::PointXY>* pts, std::string name);
107  int create_polygon_from_pts_list(const pcl::PointCloud<pcl::PointXYZ>* vertexes, pcl::PointCloud<pcl::PointXYZ>* vertices);
108  float get_weight_for_pixel(int l, int c, double resolution_factor, float px, float py, float pz);
109 
110  int set_vertex_chull(const pcl::PointCloud<pcl::PointXYZ>::Ptr vertexes);
111 
112  void compute_projectable_pixels(void);
113  int compute_pixel_list_to_vertex_list(pcl::ModelCoefficientsPtr coeff);
114 
115  //Draw
116  int draw_pixels_vector(cv::Mat* image, std::vector<pcl::PointXY>* pts, const cv::Scalar color, int thickness=1);
117  int draw_pixels_projectable(cv::Mat* image, pcl::PointCloud<pcl::PointXYZRGB>* pc, const cv::Scalar color, int thickness=1);
118  int draw_pixels_vector_as_polyline(cv::Mat* image, std::vector<pcl::PointXY>* pts, const cv::Scalar color, int thickness);
119 
120 
121  std::string projection_name;
122  cv::Mat image_original;
124  cv::Mat image_gui;
125  //cv::Mat image_hough;
126  //cv::Mat mask_hough;
127  cv::Mat image_gray;
128  cv::Mat mask_canny;
129  cv::Mat mask_grid;
132  //cv::Mat mask_tmp;
133 
134  pcl::PointCloud<pcl::PointXYZ> vertex_canvas;
135  pcl::PointCloud<pcl::PointXYZ> vertex_chull;
136  pcl::PointCloud<pcl::PointXYZ> vertex_intersection;
137  std::vector<pcl::PointXY> pixels_intersection;
138  pcl::PointCloud<pcl::PointXYZRGB> pixels_projectable;
139  pcl::PointCloud<pcl::PointXYZRGB> vertex_projectable;
140  //std::vector<float> vertex_projectable_weight;
141  //cv::vector<cv::Vec4i> lines;
142 
143 
144  pcl::PointCloud<pcl::PointXYZRGB> pixel_list;
145  pcl::PointCloud<pcl::PointXYZRGB> vertex_list;
146  std::vector<float> face_weight;
147 
149  // ------------------------------------------------------------------------------
150  //PRIVATE SECTION OF THE CLASS
151  // ------------------------------------------------------------------------------
152 
153  private:
154 };
155 
156 #endif
157 
int compute_pixel_list_to_vertex_list(pcl::ModelCoefficientsPtr coeff)
The class camera projection. Provides functionalities to perform projection of an image into a polygo...
cv::Vec< unsigned char, 3 > t_pixel
std::vector< pcl::PointXY > pixels_intersection
pcl::PointCloud< pcl::PointXYZ > vertex_intersection
pcl::PointCloud< pcl::PointXYZ > vertex_canvas
class_camera_projection(void)
Constructor.
int set_image(const cv::Mat *image, ros::Time time, std::string name="none")
Sets the image to be projected. Also computes the canvas, canny and grid masks.
int draw_pixels_vector(cv::Mat *image, std::vector< pcl::PointXY > *pts, const cv::Scalar color, int thickness=1)
int set_vertex_chull(const pcl::PointCloud< pcl::PointXYZ >::Ptr vertexes)
pcl::PointCloud< pcl::PointXYZRGB > pixels_projectable
int create_image_canvas_for_known_camera(const cv::Mat *image, std::vector< pcl::PointXY > *pts, std::string name)
float get_weight_for_pixel(int l, int c, double resolution_factor, float px, float py, float pz)
~class_camera_projection(void)
The destrictor. Does nothing.
this is the header for the main code that performs geometric polygonal primitives extraction ...
pcl::PointCloud< pcl::PointXYZ > vertex_chull
int create_polygon_from_pts_list(const pcl::PointCloud< pcl::PointXYZ > *vertexes, pcl::PointCloud< pcl::PointXYZ > *vertices)
Header for projection mesh.
std::vector< float > face_weight
header for pinhole projection. Defines default distortions parameters for mit dataset cameras...
int draw_pixels_projectable(cv::Mat *image, pcl::PointCloud< pcl::PointXYZRGB > *pc, const cv::Scalar color, int thickness=1)
pcl::PointCloud< pcl::PointXYZRGB > pixel_list
Distortion correction class definition.
pcl::PointCloud< pcl::PointXYZRGB > vertex_list
pcl::PointCloud< pcl::PointXYZRGB > vertex_projectable
int draw_pixels_vector_as_polyline(cv::Mat *image, std::vector< pcl::PointXY > *pts, const cv::Scalar color, int thickness)
int create_image_canvas(const cv::Mat *image, std::vector< pcl::PointXY > *pts)
Creates the image canvas pixels list and stores it to.


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