36 #ifndef _CAMERA_PROJECTION_H_
37 #define _CAMERA_PROJECTION_H_
39 #define PFLN {printf("DEBUG PRINT FILE %s LINE %d\n",__FILE__,__LINE__);}
46 #include <opencv2/imgproc/imgproc.hpp>
47 #include <opencv2/highgui/highgui.hpp>
48 #include <opencv2/core/core.hpp>
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>
60 #include <bo_polygon2d/polygon_boolean_operations.h>
64 typedef cv::Vec<unsigned char, 3>
t_pixel;
95 int set_image(
const cv::Mat* image, ros::Time time, std::string name=
"none");
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);
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.
std::string projection_name
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 ...
void compute_projectable_pixels(void)
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...
cv::Mat mask_projectable_pixels
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)
cv::Mat mask_intersection
int create_image_canvas(const cv::Mat *image, std::vector< pcl::PointXY > *pts)
Creates the image canvas pixels list and stores it to.