Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #pragma once
00018
00019 #include <opencv2/opencv.hpp>
00020
00021 #include <pcl/point_cloud.h>
00022 #include <pcl/point_types.h>
00023 #include <pcl/ModelCoefficients.h>
00024
00025 #include <Eigen/Dense>
00026 #include <Eigen/Geometry>
00027 #include <cstddef>
00028
00029 namespace camera_pose_calibration {
00030
00031 struct CalibrationInformation {
00033 std::vector<cv::Point2f> image_points;
00034
00036 pcl::PointCloud<pcl::PointXYZ>::Ptr source_cloud;
00037
00039 pcl::PointCloud<pcl::PointXYZ>::Ptr projected_source_cloud;
00040
00042 pcl::ModelCoefficients::Ptr plane_coefficients;
00043
00045 pcl::PointCloud<pcl::PointXYZ>::Ptr target_cloud;
00046
00048 std::vector<size_t> nan_indices;
00049 };
00050
00052 Eigen::Isometry3d findCalibration(
00053 cv::Mat const & image,
00054 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
00055 cv::Size const pattern_size,
00056 double pattern_distance,
00057 double neighbor_distance = 0.01,
00058 double valid_pattern_ratio_threshold = 0.7,
00059 double point_cloud_scale_x = 1.0,
00060 double point_cloud_scale_y = 1.0,
00061 CalibrationInformation * debug_information = NULL
00062 );
00063
00065 Eigen::Isometry3d findCalibration(
00066 cv::Mat const & left_image,
00067 cv::Mat const & right_image,
00068 Eigen::Matrix4d const & reprojection,
00069 cv::Size const pattern_size,
00070 double pattern_distance
00071 );
00072
00073
00074 }