35 #ifndef _CLASS_PINHOLE_PROJECTION_H_
36 #define _CLASS_PINHOLE_PROJECTION_H_
40 #include <opencv2/imgproc/imgproc.hpp>
41 #include <opencv2/highgui/highgui.hpp>
42 #include <opencv2/core/core.hpp>
44 #include <sensor_msgs/PointCloud2.h>
45 #include <pcl/ros/conversions.h>
46 #include <pcl/point_cloud.h>
47 #include <pcl/point_types.h>
54 #define PFLN {printf("File %s Line %d\n",__FILE__, __LINE__);}
struct class_pinhole_projection::@1 projection_plane
int project_pixel_to_vertex(const std::vector< pcl::PointXY > *p, pcl::PointCloud< pcl::PointXYZ > *v)
class_pinhole_projection(void)
int set_projection_plane(double a, double b, double c, double d)
Sets and gets.
int compute_transformation_matrix(void)
Computation.
~class_pinhole_projection(void)
Defines a class where the parameters of a camera are stored.
int project_pixel_with_color_to_vertex(const pcl::PointCloud< pcl::PointXYZRGB > *p, pcl::PointCloud< pcl::PointXYZRGB > *v)
int project_vertex_to_pixel(const pcl::PointCloud< pcl::PointXYZ >::Ptr v, std::vector< pcl::PointXY > *p)
Projections.
int print_CvMat(cv::Mat *mat, const char *name)
Prints.