Skip to content

Commit 2f4aba4

Browse files
committed
readme
1 parent 2951536 commit 2f4aba4

6 files changed

Lines changed: 280 additions & 76 deletions

File tree

.gitignore

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -172,3 +172,5 @@ GEMstack/offboard/calibration/calibration_by_segmentation/init_proj.png
172172
GEMstack/offboard/calibration/calibration_by_segmentation/refined_proj_seg.png
173173
GEMstack/offboard/calibration/calibration_by_segmentation/refined_proj.png
174174
GEMstack/offboard/calibration/calibration_by_segmentation/extrinsic.txt
175+
176+
repo/
Lines changed: 89 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,89 @@
1+
## Table of Contents
2+
- [img2pc.py](#img2pcpy) - Camera-to-LiDAR extrinsic calibration
3+
- [get_intrinsic_by_chessboard.py](#get_intrinsic_by_chessboardpy) - Intrinsic calibration using chessboard
4+
- [intrinsic_calibration_chessboard.py](#intrinsic_calibration_chessboardpy) - Intrinsic calibration using SfM
5+
6+
---
7+
8+
## img2pc.py
9+
**Camera-to-LiDAR Extrinsic Calibration Tool**
10+
11+
Compute camera extrinsic parameters by manually selecting corresponding features in an image and point cloud.
12+
13+
### Usage
14+
```bash
15+
python3 img2pc.py \
16+
--img_path IMG_PATH \
17+
--pc_path PC_PATH \
18+
--img_intrinsics_path IMG_INTRINSICS_PATH \
19+
[--pc_transform_path PC_TRANSFORM_PATH] \
20+
[--out_path OUT_PATH] \
21+
[--n_features N_FEATURES]
22+
```
23+
#### Parameters
24+
| Parameter | Description | Format | Required | Default |
25+
|-----------|-------------|--------|----------|---------|
26+
| `--img_path` | Input image path | .png | Yes | - |
27+
| `--pc_path` | Point cloud path | .npz | Yes | - |
28+
| `--img_intrinsics_path` | Camera intrinsics file | .yaml | Yes | - |
29+
| `--pc_transform_path` | LiDAR extrinsic transform | .yaml | No | Identity |
30+
| `--out_path` | Output extrinsic path | .yaml | No | None |
31+
| `--n_features` | Manual feature points | int | No | 8 |
32+
33+
### Example
34+
```bash
35+
root='/mnt/GEMstack'
36+
python3 img2pc.py \
37+
--img_path $root/data/calib1/img/fl/fl16.png \
38+
--pc_path $root/data/calib1/pc/ouster16.npz \
39+
--pc_transform_path $root/GEMstack/knowledge/calibration/gem_e4_ouster.yaml \
40+
--img_intrinsics_path $root/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml \
41+
--n_features 4 \
42+
--out_path $root/GEMstack/knowledge/calibration/gem_e4_oak.yaml
43+
```
44+
45+
## get_intrinsic_by_chessboard.py
46+
Chessboard-based Intrinsic Calibration
47+
48+
Compute camera intrinsic parameters using multiple images of a chessboard pattern.
49+
50+
### Usage
51+
```bash
52+
python3 get_intrinsic_by_chessboard.py IMG_DIR WIDTH HEIGHT [OUTPUT_PATH]
53+
```
54+
55+
### Parameters
56+
| Parameter | Description | Required |
57+
|-----------|-------------|----------|
58+
| `IMG_DIR` | Calibration images folder | Yes |
59+
| `WIDTH` | Chessboard width (squares-1) | Yes |
60+
| `HEIGHT` | Chessboard height (squares-1) | Yes |
61+
| `OUTPUT_PATH` | Output .yaml path | No |
62+
63+
64+
## get_intrinsic_by_SfM.py
65+
66+
Compute camera intrinsic parameters using Structure-from-Motion on a sequence of images.
67+
68+
### Usage
69+
```bash
70+
python3 intrinsic_calibration_chessboard.py \
71+
--input_imgs INPUT_IMGS [INPUT_IMGS ...] \
72+
--workspace WORKSPACE \
73+
[--out_file OUT_FILE]
74+
```
75+
### Parameters
76+
| Parameter | Description | Required |
77+
|-----------|-------------|----------|
78+
| `--input_imgs` | Input images (glob pattern) | Yes |
79+
| `--workspace` | Temporary directory path | Yes |
80+
| `--out_file` | Output .yaml path | No |
81+
82+
### Example
83+
```bash
84+
root='/mnt/GEMstack'
85+
python3 intrinsic_calibration_chessboard.py \
86+
--input_imgs data/fl/images/0000[0-8][147].png \
87+
--workspace /tmp/SfM_intrinsic_fl \
88+
--out_file $root/GEMstack/knowledge/calibration/camera_intrinsics2/gem_e4_fl_in.yaml
89+
```
Lines changed: 116 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,116 @@
1+
import argparse
2+
import os
3+
import shutil
4+
import pycolmap
5+
import subprocess
6+
from tools.save_cali import save_in
7+
8+
def run_colmap_command(args):
9+
result = subprocess.run(args, capture_output=True, text=True)
10+
if result.returncode != 0:
11+
print(f"Command failed: {' '.join(args)}")
12+
print(f"Error: {result.stderr}")
13+
raise RuntimeError("COLMAP command failed")
14+
return result
15+
16+
def main(input_imgs, output_dir, out, refine=True):
17+
# Setup directory structure
18+
workspace_dir = os.path.join(output_dir, 'sfm_workspace')
19+
image_dir = os.path.join(workspace_dir, 'images')
20+
os.makedirs(image_dir, exist_ok=True)
21+
22+
# Copy images to workspace
23+
print(f"Copying images to workspace...")
24+
for path in input_imgs:
25+
filename = path.split('/')[-1]
26+
dst = os.path.join(image_dir, filename)
27+
shutil.copy(path, dst)
28+
29+
# Create database path
30+
database_path = os.path.join(workspace_dir, 'database.db')
31+
if os.path.exists(database_path):
32+
os.remove(database_path)
33+
34+
# Feature extraction
35+
print("Extracting features...")
36+
# pycolmap.extract_features(
37+
# database_path, image_dir,
38+
# camera_mode=pycolmap.CameraMode.SINGLE,
39+
# camera_model=pycolmap.CameraModelId.OPENCV
40+
# )
41+
run_colmap_command([
42+
"colmap", "feature_extractor",
43+
"--database_path", database_path,
44+
"--image_path", image_dir,
45+
"--ImageReader.single_camera", "1",
46+
"--ImageReader.camera_model", "OPENCV",
47+
"--SiftExtraction.estimate_affine_shape", "1",
48+
"--SiftExtraction.domain_size_pooling", "1"
49+
])
50+
51+
# Feature matching
52+
print("Matching features...")
53+
match_options = pycolmap.SequentialMatchingOptions()
54+
match_options.overlap = 2
55+
pycolmap.match_sequential(
56+
database_path,
57+
matching_options=match_options
58+
)
59+
# Run SfM reconstruction
60+
mapper_options = pycolmap.IncrementalPipelineOptions()
61+
if refine:
62+
mapper_options.ba_refine_focal_length = 1
63+
mapper_options.ba_refine_principal_point = 1
64+
mapper_options.ba_refine_extra_params = 1
65+
else:
66+
mapper_options.ba_refine_focal_length = 0
67+
mapper_options.ba_refine_principal_point = 0
68+
mapper_options.ba_refine_extra_params = 0
69+
70+
print("Running incremental SfM...")
71+
output_path = os.path.join(workspace_dir, 'sparse')
72+
os.makedirs(output_path, exist_ok=True)
73+
reconstructions = pycolmap.incremental_mapping(
74+
database_path=database_path,
75+
image_path=image_dir,
76+
output_path=output_path,
77+
options=mapper_options
78+
)
79+
80+
# Process results
81+
if not reconstructions:
82+
print("SfM failed to reconstruct the scene!")
83+
return
84+
85+
camera:pycolmap._core.Camera = 0
86+
print("\nCamera calibration parameters:")
87+
for idx, reconstruction in reconstructions.items():
88+
print(f"\nReconstruction {idx + 1}:")
89+
for camera_id, camera in reconstruction.cameras.items():
90+
print(f"\nCamera ID {camera_id}:")
91+
print(f"Model: {camera.model}")
92+
print(f"Parameters: {camera.params}")
93+
print(f"Parameters info: {camera.params_info}")
94+
# print(f"Focal length: {camera.focal_length}")
95+
print(f"Focal length x: {camera.focal_length_x}")
96+
print(f"Focal length y: {camera.focal_length_y}")
97+
print(f"Principal point x: {camera.principal_point_x}")
98+
print(f"Principal point y: {camera.principal_point_y}")
99+
save_in(
100+
path=out,
101+
focal=[camera.focal_length_x,camera.focal_length_y],
102+
center=[camera.principal_point_x,camera.principal_point_y],
103+
distort=list(camera.params[4:])+[0.0],
104+
)
105+
print("\nCalibration complete! Results saved to:", workspace_dir)
106+
107+
if __name__ == "__main__":
108+
parser = argparse.ArgumentParser(description='Camera calibration using SfM')
109+
parser.add_argument('--input_imgs','-i', nargs='+', help='List of input imgs', required=True)
110+
parser.add_argument('--workspace','-w', type=str, required=True,
111+
help='Output directory for results')
112+
parser.add_argument('--out_file','-o', type=str, required=True,
113+
help='output yaml file')
114+
args = parser.parse_args()
115+
116+
main(args.input_imgs, args.workspace, args.out_file)
Lines changed: 64 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,64 @@
1+
import cv2
2+
import numpy as np
3+
from tools.save_cali import save_in
4+
5+
import glob
6+
def estimate_intrinsics(image_dir, checkerboard_size):
7+
criteria = (cv2.TERM_CRITERIA_EPS + cv2.TERM_CRITERIA_MAX_ITER, 30, 0.001)
8+
9+
w,h = checkerboard_size
10+
objp = np.zeros((w*h,3), np.float32)
11+
objp[:,:2] = np.mgrid[0:w,0:h].T.reshape(-1,2)
12+
13+
objpoints = []
14+
imgpoints = []
15+
images = glob.glob(image_dir + '*.png')
16+
for fname in images:
17+
img = cv2.imread(fname)
18+
19+
gray = cv2.cvtColor(img,cv2.COLOR_BGR2GRAY)
20+
21+
ret, corners = cv2.findChessboardCorners(gray, (w,h),None)
22+
23+
if ret == True:
24+
objpoints.append(objp)
25+
26+
corners2 = cv2.cornerSubPix(gray,corners,(11,11),(-1,-1),criteria)
27+
imgpoints.append(corners2)
28+
29+
img = cv2.drawChessboardCorners(img, (w,h), corners2,ret)
30+
cv2.imshow('img',img)
31+
cv2.waitKey(500)
32+
33+
cv2.destroyAllWindows()
34+
ret, mtx, dist, rvecs, tvecs = cv2.calibrateCamera(objpoints, imgpoints, gray.shape[::-1],None,None)
35+
36+
return {
37+
'fx': mtx[0,0],
38+
'fy': mtx[1,1],
39+
'cx': mtx[0,2],
40+
'cy': mtx[1,2],
41+
'distortion_coeffs': dist[0].tolist()
42+
}
43+
44+
if __name__ == "__main__":
45+
import sys
46+
if len(sys.argv) < 4:
47+
print(f"Usage: python3 this.py <image_path> <checkerboard_w> <checkerboard_h> [output_path]")
48+
sys.exit(1)
49+
50+
try:
51+
image_path = sys.argv[1]
52+
w = int(sys.argv[2])
53+
h = int(sys.argv[3])
54+
params = estimate_intrinsics(image_path, (w,h))
55+
print("Camera Intrinsics:")
56+
print(f"Focal Length (fx, fy): {params['fx']:.2f}, {params['fy']:.2f}")
57+
print(f"Principal Point (cx, cy): {params['cx']:.2f}, {params['cy']:.2f}")
58+
print(f"Distortion Coefficients: {params['distortion_coeffs']}")
59+
except Exception as e:
60+
print(f"Error: {str(e)}")
61+
62+
if len(sys.argv) == 5:
63+
out_path = sys.argv[4]
64+
save_in(out_path, focal=[params['fx'],params['fy']], center=[params['cx'],params['cy']],distort=params['distortion_coeffs'],skew=0)

GEMstack/offboard/calibration/intrinsic_calibration.py

Lines changed: 0 additions & 73 deletions
This file was deleted.

GEMstack/offboard/calibration/tools/save_cali.py

Lines changed: 9 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,8 @@ def load_in(path,mode='matrix',return_distort=False):
6161
'skew':np.array(y['skew']),
6262
'distort':np.array(y['distort'])}
6363

64-
def save_in(path,focal=None,center=None,skew=None,distort=None,matrix=None):
64+
from collections.abc import Iterable
65+
def save_in(path,focal=None,center=None,skew=0,distort=[0.0]*5,matrix=None):
6566
if matrix is not None:
6667
focal = matrix.diagonal()[0,-1]
6768
skew = matrix[0,1]
@@ -71,11 +72,16 @@ def save_in(path,focal=None,center=None,skew=None,distort=None,matrix=None):
7172
ret = {}
7273
ret['focal'] = focal
7374
ret['center'] = center
74-
ret['skew'] = skew or 0
75-
ret['distort'] = distort or [0,0,0,0,0]
75+
ret['skew'] = skew
76+
assert len(distort) in [4,5]
77+
ret['distort'] = distort
78+
if len(ret['distort']) == 4:
79+
ret['distort'] = list(ret['distort'])+[0.0]
7680
for i in ret:
7781
if type(ret[i]) == np.ndarray:
7882
ret[i] = ret[i].tolist()
83+
if isinstance(ret[i],Iterable):
84+
ret[i] = [*map(float,ret[i])]
7985
print(yaml.dump(ret,Dumper=SafeDumper,default_flow_style=False))
8086
with open(path,'w') as stream:
8187
yaml.dump(ret,stream,Dumper=SafeDumper,default_flow_style=False)

0 commit comments

Comments
 (0)