mirror of
https://gitlab.freedesktop.org/monado/monado.git
synced 2025-01-19 13:18:32 +00:00
t/calibration: Move more data storage to C portion
This commit is contained in:
parent
43c366ad41
commit
f8ee9281f8
|
@ -51,9 +51,19 @@ public:
|
|||
{
|
||||
// clang-format off
|
||||
camera_translation_mat = cv::Mat(3, 1, CV_64F, &camera_translation[0]);
|
||||
camera_rotation_mat = cv::Mat(3, 3, CV_64F, &camera_rotation[0]);
|
||||
camera_essential_mat = cv::Mat(3, 3, CV_64F, &camera_essential[0]);
|
||||
camera_fundamental_mat = cv::Mat(3, 3, CV_64F, &camera_fundamental[0]);
|
||||
camera_rotation_mat = cv::Mat(3, 3, CV_64F, &camera_rotation[0][0]);
|
||||
camera_essential_mat = cv::Mat(3, 3, CV_64F, &camera_essential[0][0]);
|
||||
camera_fundamental_mat = cv::Mat(3, 3, CV_64F, &camera_fundamental[0][0]);
|
||||
|
||||
l_intrinsics_mat = cv::Mat(3, 3, CV_64F, &l_intrinsics[0][0]);
|
||||
l_distortion_mat = cv::Mat(1, 5, CV_64F, &l_distortion[0]);
|
||||
l_rotation_mat = cv::Mat(3, 3, CV_64F, &l_rotation[0][0]);
|
||||
l_projection_mat = cv::Mat(3, 4, CV_64F, &l_projection[0][0]);
|
||||
|
||||
r_intrinsics_mat = cv::Mat(3, 3, CV_64F, &r_intrinsics[0][0]);
|
||||
r_distortion_mat = cv::Mat(1, 5, CV_64F, &r_distortion[0]);
|
||||
r_rotation_mat = cv::Mat(3, 3, CV_64F, &r_rotation[0][0]);
|
||||
r_projection_mat = cv::Mat(3, 4, CV_64F, &r_projection[0][0]);
|
||||
// clang-format on
|
||||
}
|
||||
|
||||
|
@ -63,7 +73,19 @@ public:
|
|||
return camera_rotation_mat.size() == cv::Size(3, 3) &&
|
||||
camera_translation_mat.size() == cv::Size(1, 3) &&
|
||||
camera_essential_mat.size() == cv::Size(3, 3) &&
|
||||
camera_fundamental_mat.size() == cv::Size(3, 3);
|
||||
camera_fundamental_mat.size() == cv::Size(3, 3) &&
|
||||
l_intrinsics_mat.size() == cv::Size(3, 3) &&
|
||||
l_distortion_mat.size() == cv::Size(5, 1) &&
|
||||
l_distortion_fisheye_mat.size() == cv::Size(0, 0) &&
|
||||
l_translation_mat.size() == cv::Size(0, 0) &&
|
||||
l_rotation_mat.size() == cv::Size(3, 3) &&
|
||||
l_projection_mat.size() == cv::Size(4, 3) &&
|
||||
r_intrinsics_mat.size() == cv::Size(3, 3) &&
|
||||
r_distortion_mat.size() == cv::Size(5, 1) &&
|
||||
r_distortion_fisheye_mat.size() == cv::Size(0, 0) &&
|
||||
r_translation_mat.size() == cv::Size(0, 0) &&
|
||||
r_rotation_mat.size() == cv::Size(3, 3) &&
|
||||
r_projection_mat.size() == cv::Size(4, 3);
|
||||
}
|
||||
};
|
||||
|
||||
|
|
|
@ -236,17 +236,39 @@ struct t_calibration_raw_data
|
|||
struct xrt_size image_size_pixels;
|
||||
struct xrt_size new_image_size_pixels;
|
||||
|
||||
//! Translation between thw two cameras, in the stereo pair.
|
||||
//! Translation between the two cameras, in the stereo pair.
|
||||
double camera_translation[3];
|
||||
|
||||
//! Rotation matrix between the two cameras, in the stereo pair.
|
||||
double camera_rotation[3][3];
|
||||
|
||||
//! Essential matrix.
|
||||
double camera_essential[3][3];
|
||||
|
||||
//! Fundamental matrix.
|
||||
double camera_fundamental[3][3];
|
||||
|
||||
//! Left camera intrinsics
|
||||
double l_intrinsics[3][3];
|
||||
//! Left camera distortion
|
||||
double l_distortion[5];
|
||||
//! Left rectification transform (rotation matrix).
|
||||
double l_rotation[3][3];
|
||||
//! Left projection matrix in the new (rectified) coordinate systems.
|
||||
double l_projection[3][4];
|
||||
|
||||
//! Right camera intrinsics
|
||||
double r_intrinsics[3][3];
|
||||
//! Right camera distortion
|
||||
double r_distortion[5];
|
||||
//! Right rectification transform (rotation matrix).
|
||||
double r_rotation[3][3];
|
||||
//! Right projection matrix in the new (rectified) coordinate systems.
|
||||
double r_projection[3][4];
|
||||
|
||||
#if 0
|
||||
double r_translation[3]; // [0 x 0] [1 x 3]??
|
||||
double r_distortion_fisheye[4]; // [0 x 0] [4 x 1]??
|
||||
double l_translation[3]; // [0 x 0] [1 x 3]??
|
||||
double l_distortion_fisheye[4]; // [0 x 0] [4 x 1]??
|
||||
#endif
|
||||
};
|
||||
|
||||
/*!
|
||||
|
|
Loading…
Reference in a new issue