Skip to content

Commit 55f6a6d

Browse files
committed
Updated to include command line arguments
1 parent e842aea commit 55f6a6d

1 file changed

Lines changed: 63 additions & 53 deletions

File tree

GEMstack/offboard/calibration/test_transforms.py

Lines changed: 63 additions & 53 deletions
Original file line numberDiff line numberDiff line change
@@ -1,60 +1,70 @@
11
import numpy as np
22
import cv2
33
import matplotlib.pyplot as plt
4+
import argparse
45

5-
# Load LiDAR points
6-
lidar_data = np.load("./data/lidar1.npz") # Update filename if needed
7-
lidar_points = lidar_data['arr_0'] # Ensure the correct key
6+
def load_lidar_data(lidar_path):
7+
lidar_data = np.load(lidar_path)
8+
return lidar_data['arr_0'] # Ensure the correct key
89

9-
# Load Camera Image
10-
image = cv2.imread("./data/color1.png") # Update filename if needed
11-
image = cv2.cvtColor(image, cv2.COLOR_BGR2RGB) # Convert BGR to RGB
10+
def load_image(image_path):
11+
image = cv2.imread(image_path)
12+
return cv2.cvtColor(image, cv2.COLOR_BGR2RGB) #convert BGR2RGB
1213

13-
# Transformation Matrix
14-
import numpy as np
14+
def main(lidar_path, image_path):
15+
# Load Data
16+
lidar_points = load_lidar_data(lidar_path)
17+
image = load_image(image_path)
18+
19+
# Transformation Matrix
20+
T_lidar_camera = np.array([
21+
[ 2.89748006e-02, -9.99580136e-01, 3.68439439e-05, -3.07300513e-02],
22+
[-9.49930618e-03, -3.12215512e-04, -9.99954834e-01, -3.86689354e-01],
23+
[ 9.99534999e-01, 2.89731321e-02, -9.50437214e-03, -6.71425124e-01],
24+
[ 0.00000000e+00, 0.00000000e+00, 0.00000000e+00, 1.00000000e+00]
25+
])
26+
27+
# Convert LiDAR points to homogeneous coordinates
28+
num_points = lidar_points.shape[0]
29+
lidar_homogeneous = np.hstack((lidar_points, np.ones((num_points, 1))))
30+
31+
# Transform LiDAR points to Camera Frame
32+
lidar_points_camera = (T_lidar_camera @ lidar_homogeneous.T).T
33+
34+
# Intrinsic Camera Matrix
35+
K = np.array([
36+
[684.83331299, 0. , 573.37109375],
37+
[ 0. , 684.60968018, 363.70092773],
38+
[ 0. , 0. , 1. ]
39+
], dtype=np.float32)
40+
41+
# Extract 3D points in camera frame
42+
X_c, Y_c, Z_c = lidar_points_camera[:, 0], lidar_points_camera[:, 1], lidar_points_camera[:, 2]
43+
44+
# Avoid division by zero
45+
valid = Z_c > 0
46+
X_c, Y_c, Z_c = X_c[valid], Y_c[valid], Z_c[valid]
47+
48+
# Project points onto image plane
49+
u = (K[0, 0] * X_c / Z_c) + K[0, 2]
50+
v = (K[1, 1] * Y_c / Z_c) + K[1, 2]
51+
52+
# Filter points within image bounds
53+
img_h, img_w, _ = image.shape
54+
valid_pts = (u >= 0) & (u < img_w) & (v >= 0) & (v < img_h)
55+
u, v = u[valid_pts], v[valid_pts]
56+
57+
# Plot projected points on camera image
58+
plt.imshow(image)
59+
plt.scatter(u, v, s=2, c='r')
60+
plt.title("Projected LiDAR Points on Camera Image")
61+
plt.show()
62+
63+
if __name__ == "__main__":
64+
parser = argparse.ArgumentParser(description="Project LiDAR points onto a camera image.")
65+
parser.add_argument("--lidar", type=str, required=True, help="Path to the LiDAR .npz file")
66+
parser.add_argument("--image", type=str, required=True, help="Path to the camera image")
67+
args = parser.parse_args()
68+
69+
main(args.lidar, args.image)
1570

16-
T_lidar_camera = np.array([
17-
[ 2.89748006e-02, -9.99580136e-01, 3.68439439e-05, -3.07300513e-02],
18-
[-9.49930618e-03, -3.12215512e-04, -9.99954834e-01, -3.86689354e-01],
19-
[ 9.99534999e-01, 2.89731321e-02, -9.50437214e-03, -6.71425124e-01],
20-
[ 0.00000000e+00, 0.00000000e+00, 0.00000000e+00, 1.00000000e+00]
21-
])
22-
23-
24-
# Convert LiDAR points to homogeneous coordinates
25-
num_points = lidar_points.shape[0]
26-
lidar_homogeneous = np.hstack((lidar_points, np.ones((num_points, 1)))) # (N, 4)
27-
28-
# Transform LiDAR points to Camera Frame
29-
lidar_points_camera = (T_lidar_camera @ lidar_homogeneous.T).T # (N, 4)
30-
31-
# intrinsic matrix
32-
K = np.array([
33-
[684.83331299, 0. , 573.37109375],
34-
[ 0. , 684.60968018, 363.70092773],
35-
[ 0. , 0. , 1. ]
36-
], dtype=np.float32)
37-
38-
# Extract 3D points in camera frame
39-
X_c = lidar_points_camera[:, 0]
40-
Y_c = lidar_points_camera[:, 1]
41-
Z_c = lidar_points_camera[:, 2] # Depth
42-
43-
# Avoid division by zero
44-
valid = Z_c > 0
45-
X_c, Y_c, Z_c = X_c[valid], Y_c[valid], Z_c[valid]
46-
47-
# Project points onto image plane
48-
u = (K[0, 0] * X_c / Z_c) + K[0, 2]
49-
v = (K[1, 1] * Y_c / Z_c) + K[1, 2]
50-
51-
# Filter points within image bounds
52-
img_h, img_w, _ = image.shape
53-
valid_pts = (u >= 0) & (u < img_w) & (v >= 0) & (v < img_h)
54-
u, v = u[valid_pts], v[valid_pts]
55-
56-
# Plot projected points on camera image
57-
plt.imshow(image)
58-
plt.scatter(u, v, s=2, c='r') # Red dots for projected points
59-
plt.title("Projected LiDAR Points on Camera Image")
60-
plt.show()

0 commit comments

Comments
 (0)