00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00033 #ifndef _CAMERA_PARAMETERS_H_
00034 #define _CAMERA_PARAMETERS_H_
00035 
00036 
00037 
00040 #include <ros/ros.h>
00041 
00042 #include <opencv2/imgproc/imgproc.hpp> 
00043 #include <opencv2/highgui/highgui.hpp>
00044 #include <opencv2/core/core.hpp>
00045 #include <sensor_msgs/PointCloud2.h>
00046 #include <pcl/ros/conversions.h>
00047 #include <pcl/point_cloud.h>
00048 #include <pcl/point_types.h>
00049 #include <pcl_ros/point_cloud.h>
00050 
00051 #include <tf/tf.h>
00052 
00053 
00054 class class_camera_parameters
00055 {
00056         
00057         
00058         
00059         public:
00060 
00061                 
00062                 class_camera_parameters(void)
00063                 {
00064                         intrinsic.create(3, 4, CV_64FC1); 
00065                         extrinsic.create(4, 4, CV_64FC1); 
00066                         extrinsic_inverse.create(4, 4, CV_64FC1); 
00067                         distortion.create(1, 5, CV_64FC1); 
00068                 };
00069 
00070                 
00071                 ~class_camera_parameters(void)
00072                 {
00073                 
00074                 };
00075 
00076                 int set_intrinsic(double fx, double fy, double cx, double cy);
00077                 int set_extrinsic(double p11, double p12, double p13, double p14,
00078                                       double p21, double p22, double p23, double p24,
00079                                       double p31, double p32, double p33, double p34);
00080                 int set_extrinsic(tf::StampedTransform* t);
00081                 int set_extrinsic(tf::Transform* t);
00082 
00083                 int set_distortion(double k1, double k2, double p1, double p2, double k3)
00084                 {
00085                         cv::Mat *M = &distortion;
00086                         M->at<double>(0,0) = k1; M->at<double>(0,1) = k2; M->at<double>(0,2) = p1; M->at<double>(0,3) = p2; M->at<double>(0,4) = k3;
00087                         return 1;
00088                 }
00089 
00090                 int set_distortion_spherical(double calibration_width, double calibration_height, double cx, double cy, double param, double image_scale=1)
00091                 {
00092                         spherical_distortion_params.cx=cx;
00093                         spherical_distortion_params.cy=cy;
00094                         spherical_distortion_params.param=param;
00095                         spherical_distortion_params.scale=image_scale;
00096                         spherical_distortion_params.calibration_width=calibration_width;
00097                         spherical_distortion_params.calibration_height=calibration_height;
00098                         return 1;
00099                 }
00100 
00101                 int set_width_height_num_channels(int w, int h, int nc)
00102                 {
00103                         width = w;
00104                     height = h;
00105                         num_channels = nc;      
00106                         return 1;
00107                 }
00108 
00109         cv::Mat distortion; 
00110         cv::Mat intrinsic;  
00111         cv::Mat extrinsic;  
00112         cv::Mat extrinsic_inverse;  
00113         cv::Mat transformation;  
00114         std::vector<pcl::PointXY> pixels_canvas; 
00115         ros::Time stamp;
00116         int width;
00117         int height;
00118         int num_channels;
00119         tf::StampedTransform camera_6dof_position;
00120 
00121         struct
00122         {
00123         double calibration_width;
00124         double calibration_height;
00125         double cx,cy,param;
00126         double scale;
00127         }spherical_distortion_params;
00128 };
00129 
00130 #endif
00131