From b2c7d0cb5e29391738f542dc8057ddcf2ae5f1ae Mon Sep 17 00:00:00 2001 From: samfreund Date: Sat, 27 Dec 2025 02:09:42 -0600 Subject: [PATCH 1/4] bump mrcal to 2.5 --- mrcal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mrcal b/mrcal index 0d5426b..c311b0a 160000 --- a/mrcal +++ b/mrcal @@ -1 +1 @@ -Subproject commit 0d5426b5851be80dd8e51470a0784a73565a3006 +Subproject commit c311b0acdb29d3f6c1a5abeaf17dc6a7e2ab10d9 From 33d11c5b00d6b341ec4f332550d9f4e48f07151d Mon Sep 17 00:00:00 2001 From: samfreund Date: Sat, 27 Dec 2025 02:15:24 -0600 Subject: [PATCH 2/4] fix cmake --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index d5bda09..7abfe6e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -141,7 +141,7 @@ set( src/mrcal_wrapper.cpp src/mrcal_jni.cpp libdogleg/dogleg.c - mrcal/mrcal.c mrcal/cahvore.cc mrcal/poseutils-opencv.c mrcal/poseutils-uses-autodiff.cc mrcal/poseutils.c mrcal/poseutils-opencv.c mrcal/mrcal-opencv.c mrcal/triangulation.cc + mrcal/mrcal.c mrcal/cahvore.cc mrcal/poseutils-opencv.c mrcal/poseutils-uses-autodiff.cc mrcal/poseutils.c mrcal/poseutils-opencv.c mrcal/opencv.c mrcal/triangulation.cc ) From c89102c87e349fd75e1b45277e9a9dab16efad99 Mon Sep 17 00:00:00 2001 From: samfreund Date: Sat, 27 Dec 2025 02:31:18 -0600 Subject: [PATCH 3/4] fix mrcal_num_measurements args --- src/mrcal_wrapper.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/mrcal_wrapper.cpp b/src/mrcal_wrapper.cpp index 2be5add..b1634a3 100644 --- a/src/mrcal_wrapper.cpp +++ b/src/mrcal_wrapper.cpp @@ -135,8 +135,8 @@ static std::unique_ptr mrcal_calibrate( int Ncameras_extrinsics = 0; // Seems to always be zero for single camera int Nframes = frames_rt_toref.size(); // Number of pictures of the object we've got - // mrcal_observation_point_triangulated_t *observations_point_triangulated = - // NULL; + mrcal_observation_point_triangulated_t *observations_point_triangulated = + NULL; if (!lensmodel_one_validate_args(&mrcal_lensmodel, intrinsics, false)) { auto ret = std::make_unique(); @@ -146,8 +146,8 @@ static std::unique_ptr mrcal_calibrate( int Nmeasurements = mrcal_num_measurements( Nobservations_board, Nobservations_point, - // observations_point_triangulated, - // 0, // hard-coded to 0 + observations_point_triangulated, + 0, // hard-coded to 0 calibration_object_width_n, calibration_object_height_n, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, problem_selections, &mrcal_lensmodel); From 574a1a65b17da2ea816d26a157081b7c52d57ebc Mon Sep 17 00:00:00 2001 From: samfreund Date: Sat, 27 Dec 2025 02:42:18 -0600 Subject: [PATCH 4/4] some more arg fixing --- src/mrcal_wrapper.cpp | 15 +++++++-------- 1 file changed, 7 insertions(+), 8 deletions(-) diff --git a/src/mrcal_wrapper.cpp b/src/mrcal_wrapper.cpp index b1634a3..765b2bd 100644 --- a/src/mrcal_wrapper.cpp +++ b/src/mrcal_wrapper.cpp @@ -91,7 +91,7 @@ static std::unique_ptr mrcal_calibrate( // Pool is the raw observation backing array mrcal_point3_t *c_observations_board_pool = (observations_board.data()); - // mrcal_point3_t *c_observations_point_pool = observations_point; + mrcal_point3_t *c_observations_point_pool = observations_point; // Copy from board/point pool above, using some code borrowed from // mrcal-pywrap @@ -135,8 +135,6 @@ static std::unique_ptr mrcal_calibrate( int Ncameras_extrinsics = 0; // Seems to always be zero for single camera int Nframes = frames_rt_toref.size(); // Number of pictures of the object we've got - mrcal_observation_point_triangulated_t *observations_point_triangulated = - NULL; if (!lensmodel_one_validate_args(&mrcal_lensmodel, intrinsics, false)) { auto ret = std::make_unique(); @@ -144,10 +142,11 @@ static std::unique_ptr mrcal_calibrate( return ret; } + + int Nmeasurements = mrcal_num_measurements( Nobservations_board, Nobservations_point, - observations_point_triangulated, - 0, // hard-coded to 0 + NULL, 0, // We don't use these, so pass nulls calibration_object_width_n, calibration_object_height_n, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, problem_selections, &mrcal_lensmodel); @@ -179,15 +178,15 @@ static std::unique_ptr mrcal_calibrate( Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, c_observations_board, c_observations_point, Nobservations_board, Nobservations_point, - // observations_point_triangulated, -1, - c_observations_board_pool, &mrcal_lensmodel, c_imagersizes, + NULL, -1, // We don't use these, so pass nulls + c_observations_board_pool, c_observations_point_pool, &mrcal_lensmodel, c_imagersizes, problem_selections, &problem_constants, calibration_object_spacing, calibration_object_width_n, calibration_object_height_n, verbose, false); std::vector residuals = {c_x_final, c_x_final + Nmeasurements}; return std::make_unique( true, intrinsics, stats.rms_reproj_error__pixels, residuals, - calobject_warp, stats.Noutliers); + calobject_warp, stats.Noutliers_board); } struct MrcalSolveOptions {