Skip to content

Commit 7a14b5c

Browse files
authored
Implement incremental solve and fix non-square targets (#3)
2 parents da8c4e9 + fee5e6e commit 7a14b5c

File tree

9 files changed

+307
-143
lines changed

9 files changed

+307
-143
lines changed

.gitmodules

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -7,3 +7,6 @@
77
[submodule "vcpkg"]
88
path = vcpkg
99
url = https://github.com/microsoft/vcpkg
10+
[submodule "vnlog"]
11+
path = vnlog
12+
url = https://github.com/dkogan/vnlog

.vscode/launch.json

Lines changed: 12 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -5,17 +5,23 @@
55
"version": "0.2.0",
66
"configurations": [
77
{
8-
"type": "java",
9-
"name": "MrCalJNI",
8+
"name": "Python debug calibrate cameras",
9+
"type": "debugpy",
1010
"request": "launch",
11-
"mainClass": "org.photonvision.mrcal.MrCalJNI",
12-
"projectName": "mrcal-java_a3a3fa78"
11+
"program": "/usr/bin/mrcal-calibrate-cameras",
12+
"console": "integratedTerminal",
13+
"cwd": "/home/matt/mrcal_debug_tmp/output_will/images-trimmed",
14+
"args": [
15+
"--corners-cache","corners.vnl","--lensmodel","LENSMODEL_OPENCV8","--focal","1200",
16+
"--object-spacing","0.03","--object-width-n","18","--object-height-n","13","*.png"
17+
],
18+
"justMyCode": false
1319
},
1420
{
1521
"name": "(gdb) Launch mrcal jni test",
1622
"type": "cppdbg",
1723
"request": "launch",
18-
"program": "${workspaceFolder}/build/mrcal_jni_test",
24+
"program": "${workspaceFolder}/cmake_build/bin/mrcal_jni_test",
1925
"args": [],
2026
"stopAtEntry": false,
2127
"cwd": "${workspaceFolder}",
@@ -57,4 +63,4 @@
5763
]
5864
}
5965
]
60-
}
66+
}

CMakeLists.txt

Lines changed: 4 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -15,10 +15,6 @@ if (WITH_ASAN)
1515
endif ()
1616

1717

18-
# add_library(libvnlog SHARED IMPORTED)
19-
# set_target_properties(libvnlog PROPERTIES IMPORTED_LOCATION ${SOURCE_DIR}/libvnlog.so)
20-
21-
2218
find_package(JNI)
2319
if (JNI_FOUND)
2420
# Fixes odd AWT dependency
@@ -71,7 +67,7 @@ set(
7167
src/mrcal_wrapper.cpp
7268
src/mrcal_jni.cpp
7369
libdogleg/dogleg.c
74-
mrcal/mrcal.c mrcal/cahvore.cc mrcal/poseutils-opencv.c mrcal/poseutils-uses-autodiff.cc mrcal/poseutils.c mrcal/mrcal-opencv.c
70+
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
7571
)
7672

7773

@@ -94,7 +90,7 @@ set( CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib )
9490

9591
# Create shared library
9692
add_library(mrcal_jni SHARED ${INCLUDE_HPP} ${SRC_HPP} ${SRC_CPP})
97-
target_include_directories(mrcal_jni PUBLIC ${JNI_INCLUDE_DIRS} ${OPENCV_INCLUDE_PATH} mrcal libdogleg)
93+
target_include_directories(mrcal_jni SYSTEM PUBLIC ${JNI_INCLUDE_DIRS} ${OPENCV_INCLUDE_PATH} mrcal libdogleg)
9894
add_dependencies(mrcal_jni generate_minimath)
9995

10096
IF (WIN32)
@@ -109,11 +105,11 @@ ENDIF()
109105
# Test script for checking our linker
110106
add_executable(mrcal_jni_test src/mrcal_test.cpp)
111107
target_link_libraries(mrcal_jni_test PUBLIC mrcal_jni)
112-
# target_include_directories(mrcal_jni_test PRIVATE ${VNLOG_INCLUDE_DIR})
108+
target_include_directories(mrcal_jni_test SYSTEM PRIVATE ${PROJECT_SOURCE_DIR}/vnlog)
113109
# add_dependencies(mrcal_jni_test )
114110
target_link_libraries(mrcal_jni_test PRIVATE
115111
${OpenCV_LIBS}
116-
# libvnlog
112+
${PROJECT_SOURCE_DIR}/vnlog/libvnlog.so
117113
)
118114

119115
if (WITH_ASAN)

mrcal

src/mrcal_jni.cpp

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -153,7 +153,7 @@ Java_org_photonvision_mrcal_MrCalJNI_mrcal_1calibrate_1camera
153153
total_frames_rt_toref.push_back(seed_pose);
154154
}
155155

156-
// Convert detection level to weights (we do a little memory manipulation)
156+
// Convert detection level to weights
157157
for (auto &o : observations) {
158158
double &level = o.z;
159159
if (level < 0) {
@@ -164,7 +164,11 @@ Java_org_photonvision_mrcal_MrCalJNI_mrcal_1calibrate_1camera
164164
}
165165

166166
auto statsptr = mrcal_main(observations, total_frames_rt_toref, boardSize,
167-
static_cast<double>(boardSpacing), imagerSize);
167+
static_cast<double>(boardSpacing), imagerSize,
168+
focalLenGuessMM);
169+
if (!statsptr) {
170+
return nullptr;
171+
}
168172
mrcal_result &stats = *statsptr;
169173

170174
// Find the constructor. Reference:

src/mrcal_test.cpp

Lines changed: 43 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@
3131
using namespace cv;
3232

3333
extern "C" {
34-
#include <vnlog-parser.h>
34+
#include "vnlog-parser.h"
3535
} // extern "C"
3636

3737
struct cmpByFilename {
@@ -44,16 +44,14 @@ struct cmpByFilename {
4444
};
4545

4646
int homography_test() {
47-
Size boardSize = {7, 7};
48-
Size imagerSize = {640, 480};
47+
Size boardSize = {18, 13};
48+
Size imagerSize = {1600, 1200};
4949
// std::FILE *fp =
5050
// std::fopen("/home/matt/github/photon_640_480/corners.vnl", "r");
5151
// Size boardSize = {10, 10};
5252
// Size imagerSize = {1600, 896};
5353
std::FILE *fp =
54-
std::fopen("/home/matt/Documents/GitHub/photonvision/test-resources/"
55-
"calibrationSquaresImg/piCam/640_480_1/corners.vnl",
56-
"r");
54+
std::fopen("/home/matt/mrcal_will_debug/imgs/corners.vnl", "r");
5755

5856
if (fp == NULL)
5957
return -1;
@@ -106,26 +104,36 @@ int homography_test() {
106104
observations_board.reserve(total_points);
107105
frames_rt_toref.reserve(points.size());
108106

107+
std::chrono::steady_clock::time_point begin =
108+
std::chrono::steady_clock::now();
109+
109110
for (const auto &[key, value] : points) {
110111
if (value.size()) {
111-
auto ret = getSeedPose(value.data(), boardSize, imagerSize, 0.0254, 800);
112+
auto ret = getSeedPose(value.data(), boardSize, imagerSize, 0.03, 1200);
112113

113-
if (0)
114-
std::printf("Seed pose %s: r %f %f %f t %f %f %f\n", key.c_str(),
115-
ret.r.x, ret.r.y, ret.r.z, ret.t.x, ret.t.y, ret.t.z);
114+
if (1)
115+
// std::printf("Seed pose %s: r %f %f %f t %f %f %f\n", key.c_str(),
116+
// ret.r.x, ret.r.y, ret.r.z, ret.t.x, ret.t.y, ret.t.z);
116117

117-
// Append to the Big List of board corners/levels
118-
observations_board.insert(observations_board.end(), value.begin(),
119-
value.end());
118+
// Append to the Big List of board corners/levels
119+
observations_board.insert(observations_board.end(), value.begin(),
120+
value.end());
120121
// And list of pose seeds
121122
frames_rt_toref.push_back(ret);
122123
} else {
123124
std::printf("No points for %s\n", key.c_str());
124125
}
125126
}
126127

128+
std::chrono::steady_clock::time_point end = std::chrono::steady_clock::now();
129+
std::cout << "Seed took: "
130+
<< std::chrono::duration_cast<std::chrono::milliseconds>(end -
131+
begin)
132+
.count()
133+
<< "[ms]" << std::endl;
134+
127135
auto cal_result = mrcal_main(observations_board, frames_rt_toref, boardSize,
128-
0.0254, imagerSize);
136+
0.030, imagerSize, 1200);
129137

130138
auto dt = std::chrono::steady_clock::now() - start;
131139
int dt_ms = dt.count();
@@ -135,7 +143,7 @@ int homography_test() {
135143
double max_error =
136144
*std::max_element(stats.residuals.begin(), stats.residuals.end());
137145

138-
if (0) {
146+
if (1) {
139147
std::printf("\n===============================\n\n");
140148
std::printf("RMS Reprojection Error: %.2f pixels\n", stats.rms_error);
141149
std::printf("Worst residual (by measurement): %.1f pixels\n", max_error);
@@ -145,33 +153,37 @@ int homography_test() {
145153
std::printf("calobject_warp: [%f, %f]\n", stats.calobject_warp.x2,
146154
stats.calobject_warp.y2);
147155
std::printf("dt, seeding + solve: %f ms\n", dt_ms / 1e6);
148-
std::printf("Intrinsics [%lu]:\n", stats.intrinsics.size());
156+
std::printf("Intrinsics [%lu]: ", stats.intrinsics.size());
149157
for (auto i : stats.intrinsics)
150158
std::printf("%f ", i);
151159
std::printf("\n");
152160
}
153161

154-
double fx = 100, fy = 100, cx = 50, cy = 20;
155-
cv::Mat1d camMat = (Mat_<double>(3,3) << fx, 0, cx, 0, fy, cy, 0, 0, 1);
156-
cv::Mat1d distCoeffs = (Mat_<double>(1,5) << 0.17802570252202954,-1.461379065131586,0.001019661566461145,0.0003215220840230439,2.7249642067580533);
162+
// double fx = 100, fy = 100, cx = 50, cy = 20;
163+
// cv::Mat1d camMat = (Mat_<double>(3, 3) << fx, 0, cx, 0, fy, cy, 0, 0, 1);
164+
// cv::Mat1d distCoeffs =
165+
// (Mat_<double>(1, 5) << 0.17802570252202954, -1.461379065131586,
166+
// 0.001019661566461145, 0.0003215220840230439, 2.7249642067580533);
157167

158-
undistort_mrcal(&inputs, &outputs, &camMat, &distCoeffs, CameraLensModel::LENSMODEL_OPENCV5, 0, 0, 0, 0);
168+
// undistort_mrcal(&inputs, &outputs, &camMat, &distCoeffs,
169+
// CameraLensModel::LENSMODEL_OPENCV5, 0, 0, 0, 0);
159170

160-
cv::Mat2d outputs_opencv = cv::Mat2d::zeros(inputs.size());
161-
cv::undistortImagePoints(inputs, outputs_opencv, camMat, distCoeffs,
162-
TermCriteria(TermCriteria::MAX_ITER + TermCriteria::EPS, 50,
163-
1e-4));
171+
// cv::Mat2d outputs_opencv = cv::Mat2d::zeros(inputs.size());
172+
// cv::undistortImagePoints(
173+
// inputs, outputs_opencv, camMat, distCoeffs,
174+
// TermCriteria(TermCriteria::MAX_ITER + TermCriteria::EPS, 50, 1e-4));
164175

165-
std::cout << "cam mat\n" << camMat << std::endl;
166-
std::cout << "dist\n" << distCoeffs << std::endl;
167-
std::cout << "Inputs\n" << inputs << std::endl;
168-
std::cout << "Outputs (mrcal)\n" << outputs << std::endl;
169-
std::cout << "Outputs (opencv)\n" << outputs_opencv << std::endl;
176+
// std::cout << "cam mat\n" << camMat << std::endl;
177+
// std::cout << "dist\n" << distCoeffs << std::endl;
178+
// std::cout << "Inputs\n" << inputs << std::endl;
179+
// std::cout << "Outputs (mrcal)\n" << outputs << std::endl;
180+
// std::cout << "Outputs (opencv)\n" << outputs_opencv << std::endl;
181+
182+
return 0;
170183
}
171184

172185
int main() {
173186
// for (int i = 0; i < 1e6; i++) {
174-
homography_test();
187+
homography_test();
175188
// }
176-
177189
}

0 commit comments

Comments
 (0)