33 #ifndef _CAMERA_PARAMETERS_H_
34 #define _CAMERA_PARAMETERS_H_
42 #include <opencv2/imgproc/imgproc.hpp>
43 #include <opencv2/highgui/highgui.hpp>
44 #include <opencv2/core/core.hpp>
45 #include <sensor_msgs/PointCloud2.h>
46 #include <pcl/ros/conversions.h>
47 #include <pcl/point_cloud.h>
48 #include <pcl/point_types.h>
49 #include <pcl_ros/point_cloud.h>
77 int set_extrinsic(
double p11,
double p12,
double p13,
double p14,
78 double p21,
double p22,
double p23,
double p24,
79 double p31,
double p32,
double p33,
double p34);
86 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;
~class_camera_parameters(void)
tf::StampedTransform camera_6dof_position
class_camera_parameters(void)
struct class_camera_parameters::@0 spherical_distortion_params
int set_extrinsic(double p11, double p12, double p13, double p14, double p21, double p22, double p23, double p24, double p31, double p32, double p33, double p34)
sets extrinsic parameters
int set_distortion_spherical(double calibration_width, double calibration_height, double cx, double cy, double param, double image_scale=1)
double calibration_height
int set_distortion(double k1, double k2, double p1, double p2, double k3)
cv::Mat extrinsic_inverse
std::vector< pcl::PointXY > pixels_canvas
int set_intrinsic(double fx, double fy, double cx, double cy)
sets intrinsic parameters from a 3x3 CvMat
int set_width_height_num_channels(int w, int h, int nc)