#include <opencv2/opencv.hpp>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/ModelCoefficients.h>
#include <Eigen/Dense>
#include <Eigen/Geometry>
#include <cstddef>
Go to the source code of this file.
Classes | |
struct | camera_pose_calibration::CalibrationInformation |
Namespaces | |
namespace | camera_pose_calibration |
Functions | |
Eigen::Isometry3d | camera_pose_calibration::findCalibration (cv::Mat const &image, pcl::PointCloud< pcl::PointXYZ >::Ptr cloud, cv::Size const pattern_size, double pattern_distance, double neighbor_distance=0.01, double valid_pattern_ratio_threshold=0.7, double point_cloud_scale_x=1.0, double point_cloud_scale_y=1.0, CalibrationInformation *debug_information=NULL) |
Finds the isometry for the asymmetric calibration pattern in the image and pointcloud. | |
Eigen::Isometry3d | camera_pose_calibration::findCalibration (cv::Mat const &left_image, cv::Mat const &right_image, Eigen::Matrix4d const &reprojection, cv::Size const pattern_size, double pattern_distance) |
Finds the isometry for the asymmetric calibration pattern, given two (undistorted) stereo images and a reprojection matrix. |