Skip to content

Commit 374f10d

Browse files
committed
cli argument clarified
1 parent 9b23c88 commit 374f10d

3 files changed

Lines changed: 27 additions & 18 deletions

File tree

GEMstack/offboard/calibration/README.md

Lines changed: 14 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -22,13 +22,13 @@ There are two ways to calibrate the intrinsics, depending on what data you have.
2222

2323
To use the `get_intrinsic_by_chessboard.py` script, collect a series of images with a large chessboard using either the data collection scripts or a rosbag. Select images where the chessboard is at different points in the camera frame, different distances including filling the entire frame, and at different angles. The script detects internal corners where four squares meet, so the extreme edge of the chessboard does not need to be in frame.
2424

25-
To use the `get_intrinsic_by_SfM.py` script, *[fill in here]*
25+
To use the `get_intrinsic_by_SfM.py` script, prepare a set of images recorded from the same camera going through a continuous movement, and follow [this](#get_intrinsic_by_sfmpy)
2626

2727
The `undistort_images.py` script can then be used to rectify a set of images using the calibrated intrinsics to evaluate or use in other applications.
2828

2929
**Extrinsic Calibration**
3030

31-
The `img2pc.py` file contains the main part of the extrinsic calibration process. Select a synchronized camera image and lidar pointcloud to align, ideally containing features that are easy to detect in both, such as boards or signs with corners. Alignment can be done with *[explain minimum number of points and any limitations on them]*. The first screen will ask you to select points on the image, and will close on its own once *n_features* points are selected. The second screen will ask you to select points in the point cloud, and will need to be closed manually once exactly *n_features* points are selected, or it will prompt you again. The extrinsic matrices will then be displayed, and if an *out_path* is provided they will also be saved.
31+
The `img2pc.py` file contains the main part of the extrinsic calibration process. Select a synchronized camera image and lidar pointcloud to align, ideally containing features that are easy to detect in both, such as boards or signs with corners. Alignment can be done with 4 feature pairs(must be coplanar) or 6+ points. The first screen will ask you to select points on the image, and will close on its own once *n_features* points are selected. The second screen will ask you to select points in the point cloud, and will need to be closed manually once exactly *n_features* points are selected, or it will prompt you again. The extrinsic matrices will then be displayed, and if an *out_path* is provided they will also be saved.
3232

3333
The `test_transforms.py` file can then be used to manually fine-tune the calculated intrinsics. Use the sliders to change the translation and rotation to project the lidar points onto the image more accurately.
3434

@@ -37,12 +37,14 @@ The `test_transforms.py` file can then be used to manually fine-tune the calcula
3737

3838
Compute camera extrinsic parameters by manually selecting corresponding features in an image and point cloud.
3939

40+
**Note**: On the img prompt, click n points and the window closed itself. On the pc prompt, right click n points and close the window manually.
41+
4042
### Usage
4143
```bash
4244
python3 img2pc.py \
4345
--img_path IMG_PATH \
4446
--pc_path PC_PATH \
45-
--img_intrinsics_path IMG_INTRINSICS_PATH \
47+
--img_intrinsic_path IMG_INTRINSICS_PATH \
4648
[--pc_transform_path PC_TRANSFORM_PATH] \
4749
[--out_path OUT_PATH] \
4850
[--n_features N_FEATURES]
@@ -53,10 +55,14 @@ python3 img2pc.py \
5355
|-----------|-------------|--------|----------|---------|
5456
| `--img_path` | Input image path | .png | Yes | - |
5557
| `--pc_path` | Point cloud path | .npz | Yes | - |
56-
| `--img_intrinsics_path` | Camera intrinsics file | .yaml | Yes | - |
58+
| `--img_intrinsic_path` | Camera intrinsics file | .yaml | Yes | - |
5759
| `--pc_transform_path` | LiDAR extrinsic transform | .yaml | No | Identity |
58-
| `--out_path` | Output extrinsic path | .yaml | No | None |
5960
| `--n_features` | Manual feature points | int | No | 8 |
61+
| `--out_path` | Output extrinsic path | .yaml | No | None |
62+
| `--no_undistort` | to undistort | - | - | False |
63+
| `--show` | visualize reprojection | - | - | False |
64+
65+
*`--no_undistort True` is rare because it's almost sure that extrinsic solving performs better after undistortion*
6066

6167
### Example
6268
```bash
@@ -65,7 +71,7 @@ python3 img2pc.py \
6571
--img_path $root/data/calib1/img/fl/fl16.png \
6672
--pc_path $root/data/calib1/pc/ouster16.npz \
6773
--pc_transform_path $root/GEMstack/knowledge/calibration/gem_e4_ouster.yaml \
68-
--img_intrinsics_path $root/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml \
74+
--img_intrinsic_path $root/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml \
6975
--n_features 4 \
7076
--out_path $root/GEMstack/knowledge/calibration/gem_e4_oak.yaml
7177
```
@@ -176,9 +182,10 @@ python3 intrinsic_calibration_chessboard.py \
176182
| Parameter | Description | Required |
177183
|-----------|-------------|----------|
178184
| `--input_imgs` | Input images (glob pattern) | Yes |
179-
| `--workspace` | Temporary directory path | Yes |
185+
| `--workspace` | Temporary directory path (default `/tmp/colmap_tmp`) | No |
180186
| `--out_file` | Output .yaml path | No |
181187

188+
*note:`--workspace` allows you to save running time for continuing/redoing a previous job. you can clean it up after. check [colmap](https://colmap.github.io/) for more infomation*
182189
### Example
183190
```bash
184191
root='/mnt/GEMstack'

GEMstack/offboard/calibration/get_intrinsic_by_SfM.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -107,7 +107,7 @@ def main(input_imgs, output_dir, out, refine=True):
107107
if __name__ == "__main__":
108108
parser = argparse.ArgumentParser(description='Camera calibration using SfM')
109109
parser.add_argument('--input_imgs','-i', nargs='+', help='List of input imgs', required=True)
110-
parser.add_argument('--workspace','-w', type=str, required=True,
110+
parser.add_argument('--workspace','-w', type=str, required=False, default= '/tmp/colmap_tmp',
111111
help='Output directory for results')
112112
parser.add_argument('--out_file','-o', type=str, required=True,
113113
help='output yaml file')

GEMstack/offboard/calibration/img2pc.py

Lines changed: 12 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -88,17 +88,17 @@ def main():
8888
formatter_class=argparse.ArgumentDefaultsHelpFormatter)
8989
parser.add_argument('-p', '--img_path', type=str, required=True,
9090
help='Path to PNG image')
91-
parser.add_argument('-l', '--lidar_path', type=str, required=True,
91+
parser.add_argument('-l', '--pc_path', type=str, required=True,
9292
help='Path to lidar NPZ point cloud')
93-
parser.add_argument('-t', '--lidar_transform_path', type=str, required=True,
93+
parser.add_argument('-t', '--pc_transform_path', type=str, required=True,
9494
help='Path to yaml file for lidar extrinsics')
95-
parser.add_argument('-i', '--img_intrinsics_path', type=str, required=True,
95+
parser.add_argument('-i', '--img_intrinsic_path', type=str, required=True,
9696
help='Path to yaml file for image intrinsics')
9797
parser.add_argument('-o', '--out_path', type=str, required=False,
9898
help='Path to output yaml file for image extrinsics')
9999
parser.add_argument('-n', '--n_features', type=int, required=False, default=8,
100100
help='Number of features to select and math')
101-
parser.add_argument('-u','--undistort', action='store_true',
101+
parser.add_argument('-u','--no_undistort', action='store_true',
102102
help='Whether to use distortion parameters')
103103
parser.add_argument('-s', '--show', action='store_true',
104104
help='Show projected points after calibration')
@@ -109,21 +109,23 @@ def main():
109109
# Load data
110110
N = args.n_features
111111
img = cv2.imread(args.img_path, cv2.IMREAD_UNCHANGED)
112-
pc = np.load(args.lidar_path)['arr_0']
112+
pc = np.load(args.pc_path)['arr_0']
113113
pc = pc[~np.all(pc == 0, axis=1)] # remove (0,0,0)'s
114114

115-
if args.undistort:
116-
K, distort = load_in(args.img_intrinsics_path,mode='matrix',return_distort=True)
115+
if not args.no_undistort:
116+
K, distort = load_in(args.img_intrinsic_path,mode='matrix',return_distort=True)
117117
print('applying distortion coeffs', distort)
118118
h, w = img.shape[:2]
119119
newK, roi = cv2.getOptimalNewCameraMatrix(K, distort, (w,h), 1, (w,h))
120120
img = cv2.undistort(img, K, distort, None, newK)
121121
K = newK
122122
else:
123-
K = load_in(args.img_intrinsics_path,mode='matrix')
123+
K = load_in(args.img_intrinsic_path,mode='matrix')
124124

125-
lidar_ex = load_ex(args.lidar_transform_path,mode='matrix')
126-
pc = np.pad(pc,((0,0),(0,1)),constant_values=1) @ lidar_ex.T[:,:3]
125+
lidar_ex = np.eye(4)
126+
if args.pc_transform_path:
127+
lidar_ex = load_ex(args.pc_transform_path,mode='matrix')
128+
pc = np.pad(pc,((0,0),(0,1)),constant_values=1) @ lidar_ex.T[:,:3]
127129

128130
c2v = calib(args,pc,img,K,N)
129131
T = np.linalg.inv(c2v)

0 commit comments

Comments
 (0)