diff --git a/CMakeLists.txt b/CMakeLists.txt index 2f7f16b..44911a1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -153,7 +153,7 @@ set(SRC_CPP mrcal/poseutils-uses-autodiff.cc mrcal/poseutils.c mrcal/poseutils-opencv.c - mrcal/mrcal-opencv.c + mrcal/opencv.c mrcal/triangulation.cc ) diff --git a/mrcal b/mrcal index 0d5426b..c311b0a 160000 --- a/mrcal +++ b/mrcal @@ -1 +1 @@ -Subproject commit 0d5426b5851be80dd8e51470a0784a73565a3006 +Subproject commit c311b0acdb29d3f6c1a5abeaf17dc6a7e2ab10d9 diff --git a/src/mrcal_wrapper.cpp b/src/mrcal_wrapper.cpp index 3ee40bb..805a61b 100644 --- a/src/mrcal_wrapper.cpp +++ b/src/mrcal_wrapper.cpp @@ -110,7 +110,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 @@ -154,8 +154,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(); @@ -164,9 +162,8 @@ static std::unique_ptr mrcal_calibrate( } int Nmeasurements = mrcal_num_measurements( - Nobservations_board, Nobservations_point, - // observations_point_triangulated, - // 0, // hard-coded to 0 + Nobservations_board, Nobservations_point, 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); @@ -197,16 +194,16 @@ static std::unique_ptr mrcal_calibrate( c_extrinsics, c_frames, c_points, c_calobject_warp, Ncameras_intrinsics, 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, - problem_selections, &problem_constants, calibration_object_spacing, - calibration_object_width_n, calibration_object_height_n, verbose, false); + Nobservations_point, 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 {