Skip to content

Commit

Permalink
chore: ci/cd fixes
Browse files Browse the repository at this point in the history
Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>
  • Loading branch information
knzo25 committed Oct 21, 2024
1 parent a9d435c commit 5b5a148
Show file tree
Hide file tree
Showing 3 changed files with 13 additions and 38 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -181,17 +181,17 @@ void CeresCameraIntrinsicsOptimizer::dataToPlaceholders()
intrinsics_placeholder_[index++] = k6;
}

// Convert the revcs, tvecs into the placeholders
// Convert the revcs, tvecs into the placeholders // cSpell:ignore rvecs,tvecs

Check warning on line 184 in calibrators/intrinsic_camera_calibrator/ceres_intrinsic_camera_calibrator/src/ceres_camera_intrinsics_optimizer.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (revcs)
pose_placeholders_.resize(object_points_.size());

for (std::size_t i = 0; i < object_points_.size(); i++) {
cv::Mat rmat;
cv::Rodrigues(rvecs_[i], rmat);
cv::Mat rotation_cv;
cv::Rodrigues(rvecs_[i], rotation_cv);

Eigen::Vector3d translation;
Eigen::Matrix3d rotation;
cv::cv2eigen(tvecs_[i], translation);
cv::cv2eigen(rmat, rotation);
cv::cv2eigen(rotation_cv, rotation);
Eigen::Quaterniond quat(rotation);

std::array<double, POSE_OPT_DIM> & placeholder = pose_placeholders_[i];
Expand Down Expand Up @@ -367,7 +367,7 @@ void CeresCameraIntrinsicsOptimizer::solve()
}

ceres::Solver::Options options;
options.linear_solver_type = ceres::DENSE_SCHUR;
options.linear_solver_type = ceres::DENSE_SCHUR; // cSpell:ignore SCHUR
options.minimizer_progress_to_stdout = verbose_;
options.max_num_iterations = 500;
options.function_tolerance = 1e-10;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -154,6 +154,7 @@ namespace py = pybind11;

PYBIND11_MODULE(ceres_intrinsic_camera_calibrator_py, m)
{
// cSpell:ignore pbdoc,currentmodule,autosummary,toctree
m.doc() = R"pbdoc(
Ceres-based camera intrinsics calibrator module
-----------------------
Expand All @@ -177,7 +178,7 @@ PYBIND11_MODULE(ceres_intrinsic_camera_calibrator_py, m)
initial_camera_matrix (np.array): The initial camera matrix
initial_dist_coeffs (np.array): The initial distortion coefficients
num_radial_coeffs (int): The number of radial distortion coefficients used during calibration
use_tangential_distortion (bool): Whether we should use tangential distortion durin calibration
use_tangential_distortion (bool): Whether we should use tangential distortion during calibration
Returns:
The RMS reprojection error, the optimized camera intrinsics, and the board extrinsics
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -181,31 +181,6 @@ int main(int argc, char ** argv)

int flags = 0;

/* if (!use_tangent_distortion) {
flags |= cv::CALIB_ZERO_TANGENT_DIST;
}
if (num_radial_distortion_coeffs < 3) {
flags |= cv::CALIB_FIX_K3;
}
if (num_radial_distortion_coeffs < 2) {
flags |= cv::CALIB_FIX_K2;
}
if (num_radial_distortion_coeffs < 1) {
flags |= cv::CALIB_FIX_K1;
} */

/* flags |= cv2.CALIB_ZERO_TANGENT_DIST if not self.use_tangential_distortion.value else 0
flags |= cv2.CALIB_RATIONAL_MODEL if self.radial_distortion_coefficients.value > 3 else 0
flags |= cv2.CALIB_FIX_K6 if self.radial_distortion_coefficients.value < 6 else 0
flags |= cv2.CALIB_FIX_K5 if self.radial_distortion_coefficients.value < 5 else 0
flags |= cv2.CALIB_FIX_K4 if self.radial_distortion_coefficients.value < 4 else 0
flags |= cv2.CALIB_FIX_K3 if self.radial_distortion_coefficients.value < 3 else 0
flags |= cv2.CALIB_FIX_K2 if self.radial_distortion_coefficients.value < 2 else 0
flags |= cv2.CALIB_FIX_K1 if self.radial_distortion_coefficients.value < 1 else 0 */

flags |= use_tangent_distortion ? 0 : cv::CALIB_ZERO_TANGENT_DIST;
flags |= num_rational_distortion_coeffs > 0 ? cv::CALIB_RATIONAL_MODEL : 0;
flags |= num_rational_distortion_coeffs < 3 ? cv::CALIB_FIX_K6 : 0;
Expand All @@ -216,7 +191,7 @@ int main(int argc, char ** argv)
flags |= num_radial_distortion_coeffs < 1 ? cv::CALIB_FIX_K1 : 0;

auto mini_opencv_start = std::chrono::high_resolution_clock::now();
double mini_reproj_error = cv::calibrateCamera(
double mini_reprojection_error = cv::calibrateCamera(
mini_calibration_object_points, mini_calibration_image_points, size, mini_opencv_camera_matrix,
mini_opencv_dist_coeffs, mini_opencv_calibration_rvecs, mini_opencv_calibration_tvecs, flags);

Expand All @@ -237,7 +212,7 @@ int main(int argc, char ** argv)

auto opencv_start = std::chrono::high_resolution_clock::now();

double reproj_error = cv::calibrateCamera(
double reprojection_error = cv::calibrateCamera(
calibration_object_points, calibration_image_points, size, opencv_camera_matrix,
opencv_dist_coeffs, opencv_calibration_rvecs, opencv_calibration_tvecs, flags);

Expand All @@ -247,9 +222,9 @@ int main(int argc, char ** argv)
std::cout << "\tcamera_matrix: \n" << opencv_camera_matrix << std::endl;
std::cout << "\tdist_coeffs: \n" << opencv_dist_coeffs << std::endl;

std::cout << "Mini OpenCV calibration error (reported by the calibrator)=" << mini_reproj_error
<< std::endl;
std::cout << "OpenCV calibration error (reported by the calibrator)=" << reproj_error
std::cout << "Mini OpenCV calibration error (reported by the calibrator)="
<< mini_reprojection_error << std::endl;
std::cout << "OpenCV calibration error (reported by the calibrator)=" << reprojection_error
<< std::endl;

// Need to compute the whole rvecs, tvecs for the whole calibration set
Expand Down Expand Up @@ -282,9 +257,8 @@ int main(int argc, char ** argv)
optimizer.solve();
optimizer.placeholdersToData();
optimizer.evaluate();
double rms_rror = optimizer.getSolution(
[[maybe_unused]] double rms_error = optimizer.getSolution(
ceres_camera_matrix, ceres_dist_coeffs, ceres_calibration_rvecs, ceres_calibration_tvecs);
(void)rms_rror;

auto ceres_stop = std::chrono::high_resolution_clock::now();

Expand Down

0 comments on commit 5b5a148

Please sign in to comment.