-
Notifications
You must be signed in to change notification settings - Fork 119
/
calibrate_camera_lidar.py
executable file
·551 lines (444 loc) · 17.6 KB
/
calibrate_camera_lidar.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
#!/usr/bin/env python
# -*- coding: utf-8 -*-
'''
Author : Heethesh Vhavle
Email : heethesh@cmu.edu
Version : 1.2.1
Date : Jan 20, 2019
Description:
Script to find the transformation between the Camera and the LiDAR
Example Usage:
1. To perform calibration using the GUI to pick correspondences:
$ rosrun lidar_camera_calibration calibrate_camera_lidar.py --calibrate
The point correspondences will be save as following:
- PKG_PATH/calibration_data/lidar_camera_calibration/img_corners.npy
- PKG_PATH/calibration_data/lidar_camera_calibration/pcl_corners.npy
The calibrate extrinsic are saved as following:
- PKG_PATH/calibration_data/lidar_camera_calibration/extrinsics.npz
--> 'euler' : euler angles (3, )
--> 'R' : rotation matrix (3, 3)
--> 'T' : translation offsets (3, )
2. To display the LiDAR points projected on to the camera plane:
$ roslaunch lidar_camera_calibration display_camera_lidar_calibration.launch
Notes:
Make sure this file has executable permissions:
$ chmod +x calibrate_camera_lidar.py
References:
http://wiki.ros.org/message_filters
http://wiki.ros.org/cv_bridge/Tutorials/
http://docs.ros.org/api/image_geometry/html/python/
http://wiki.ros.org/ROS/Tutorials/WritingPublisherSubscribe
'''
# Python 2/3 compatibility
from __future__ import print_function
# Built-in modules
import os
import sys
import time
import threading
import multiprocessing
# External modules
import cv2
import numpy as np
import matplotlib.cm
import matplotlib.pyplot as plt
from mpl_toolkits.mplot3d import Axes3D
# ROS modules
PKG = 'lidar_camera_calibration'
import roslib; roslib.load_manifest(PKG)
import rosbag
import rospy
import tf2_ros
import ros_numpy
import image_geometry
import message_filters
from cv_bridge import CvBridge, CvBridgeError
from tf.transformations import euler_from_matrix
from tf2_sensor_msgs.tf2_sensor_msgs import do_transform_cloud
from sensor_msgs.msg import Image, CameraInfo, PointCloud2
# Global variables
OUSTER_LIDAR = False
PAUSE = False
FIRST_TIME = True
KEY_LOCK = threading.Lock()
TF_BUFFER = None
TF_LISTENER = None
CV_BRIDGE = CvBridge()
CAMERA_MODEL = image_geometry.PinholeCameraModel()
# Global paths
PKG_PATH = os.path.dirname(os.path.dirname(os.path.realpath(__file__)))
CALIB_PATH = 'calibration_data/lidar_camera_calibration'
'''
Keyboard handler thread
Inputs: None
Outputs: None
'''
def handle_keyboard():
global KEY_LOCK, PAUSE
key = raw_input('Press [ENTER] to pause and pick points\n')
with KEY_LOCK: PAUSE = True
'''
Start the keyboard handler thread
Inputs: None
Outputs: None
'''
def start_keyboard_handler():
keyboard_t = threading.Thread(target=handle_keyboard)
keyboard_t.daemon = True
keyboard_t.start()
'''
Save the point correspondences and image data
Points data will be appended if file already exists
Inputs:
data - [numpy array] - points or opencv image
filename - [str] - filename to save
folder - [str] - folder to save at
is_image - [bool] - to specify whether points or image data
Outputs: None
'''
def save_data(data, filename, folder, is_image=False):
# Empty data
if not len(data): return
# Handle filename
filename = os.path.join(PKG_PATH, os.path.join(folder, filename))
# Create folder
try:
os.makedirs(os.path.join(PKG_PATH, folder))
except OSError:
if not os.path.isdir(os.path.join(PKG_PATH, folder)): raise
# Save image
if is_image:
cv2.imwrite(filename, data)
return
# Save points data
if os.path.isfile(filename):
rospy.logwarn('Updating file: %s' % filename)
data = np.vstack((np.load(filename), data))
np.save(filename, data)
'''
Runs the image point selection GUI process
Inputs:
img_msg - [sensor_msgs/Image] - ROS sensor image message
now - [int] - ROS bag time in seconds
rectify - [bool] - to specify whether to rectify image or not
Outputs:
Picked points saved in PKG_PATH/CALIB_PATH/img_corners.npy
'''
def extract_points_2D(img_msg, now, rectify=False):
# Log PID
rospy.loginfo('2D Picker PID: [%d]' % os.getpid())
# Read image using CV bridge
try:
img = CV_BRIDGE.imgmsg_to_cv2(img_msg, 'bgr8')
except CvBridgeError as e:
rospy.logerr(e)
return
# Rectify image
if rectify: CAMERA_MODEL.rectifyImage(img, img)
disp = cv2.cvtColor(img.copy(), cv2.COLOR_BGR2RGB)
# Setup matplotlib GUI
fig = plt.figure()
ax = fig.add_subplot(111)
ax.set_title('Select 2D Image Points - %d' % now.secs)
ax.set_axis_off()
ax.imshow(disp)
# Pick points
picked, corners = [], []
def onclick(event):
x = event.xdata
y = event.ydata
if (x is None) or (y is None): return
# Display the picked point
picked.append((x, y))
corners.append((x, y))
rospy.loginfo('IMG: %s', str(picked[-1]))
if len(picked) > 1:
# Draw the line
temp = np.array(picked)
ax.plot(temp[:, 0], temp[:, 1])
ax.figure.canvas.draw_idle()
# Reset list for future pick events
del picked[0]
# Display GUI
fig.canvas.mpl_connect('button_press_event', onclick)
plt.show()
# Save corner points and image
rect = '_rect' if rectify else ''
if len(corners) > 1: del corners[-1] # Remove last duplicate
save_data(corners, 'img_corners%s.npy' % (rect), CALIB_PATH)
save_data(img, 'image_color%s-%d.jpg' % (rect, now.secs),
os.path.join(CALIB_PATH, 'images'), True)
'''
Runs the LiDAR point selection GUI process
Inputs:
velodyne - [sensor_msgs/PointCloud2] - ROS velodyne PCL2 message
now - [int] - ROS bag time in seconds
Outputs:
Picked points saved in PKG_PATH/CALIB_PATH/pcl_corners.npy
'''
def extract_points_3D(velodyne, now):
# Log PID
rospy.loginfo('3D Picker PID: [%d]' % os.getpid())
# Extract points data
points = ros_numpy.point_cloud2.pointcloud2_to_array(velodyne)
points = np.asarray(points.tolist())
# Group all beams together and pick the first 4 columns for X, Y, Z, intensity.
if OUSTER_LIDAR: points = points.reshape(-1, 9)[:, :4]
# Select points within chessboard range
inrange = np.where((points[:, 0] > 0) &
(points[:, 0] < 2.5) &
(np.abs(points[:, 1]) < 2.5) &
(points[:, 2] < 2))
points = points[inrange[0]]
print(points.shape)
if points.shape[0] > 5:
rospy.loginfo('PCL points available: %d', points.shape[0])
else:
rospy.logwarn('Very few PCL points available in range')
return
# Color map for the points
cmap = matplotlib.cm.get_cmap('hsv')
colors = cmap(points[:, -1] / np.max(points[:, -1]))
# Setup matplotlib GUI
fig = plt.figure()
ax = fig.add_subplot(111, projection='3d')
ax.set_title('Select 3D LiDAR Points - %d' % now.secs, color='white')
ax.set_axis_off()
ax.set_facecolor((0, 0, 0))
ax.scatter(points[:, 0], points[:, 1], points[:, 2], c=colors, s=2, picker=5)
# Equalize display aspect ratio for all axes
max_range = (np.array([points[:, 0].max() - points[:, 0].min(),
points[:, 1].max() - points[:, 1].min(),
points[:, 2].max() - points[:, 2].min()]).max() / 2.0)
mid_x = (points[:, 0].max() + points[:, 0].min()) * 0.5
mid_y = (points[:, 1].max() + points[:, 1].min()) * 0.5
mid_z = (points[:, 2].max() + points[:, 2].min()) * 0.5
ax.set_xlim(mid_x - max_range, mid_x + max_range)
ax.set_ylim(mid_y - max_range, mid_y + max_range)
ax.set_zlim(mid_z - max_range, mid_z + max_range)
# Pick points
picked, corners = [], []
def onpick(event):
ind = event.ind[0]
x, y, z = event.artist._offsets3d
# Ignore if same point selected again
if picked and (x[ind] == picked[-1][0] and y[ind] == picked[-1][1] and z[ind] == picked[-1][2]):
return
# Display picked point
picked.append((x[ind], y[ind], z[ind]))
corners.append((x[ind], y[ind], z[ind]))
rospy.loginfo('PCL: %s', str(picked[-1]))
if len(picked) > 1:
# Draw the line
temp = np.array(picked)
ax.plot(temp[:, 0], temp[:, 1], temp[:, 2])
ax.figure.canvas.draw_idle()
# Reset list for future pick events
del picked[0]
# Display GUI
fig.canvas.mpl_connect('pick_event', onpick)
plt.show()
# Save corner points
if len(corners) > 1: del corners[-1] # Remove last duplicate
save_data(corners, 'pcl_corners.npy', CALIB_PATH)
'''
Calibrate the LiDAR and image points using OpenCV PnP RANSAC
Requires minimum 5 point correspondences
Inputs:
points2D - [numpy array] - (N, 2) array of image points
points3D - [numpy array] - (N, 3) array of 3D points
Outputs:
Extrinsics saved in PKG_PATH/CALIB_PATH/extrinsics.npz
'''
def calibrate(points2D=None, points3D=None):
# Load corresponding points
folder = os.path.join(PKG_PATH, CALIB_PATH)
if points2D is None: points2D = np.load(os.path.join(folder, 'img_corners.npy'))
if points3D is None: points3D = np.load(os.path.join(folder, 'pcl_corners.npy'))
# Check points shape
assert(points2D.shape[0] == points3D.shape[0])
if not (points2D.shape[0] >= 5):
rospy.logwarn('PnP RANSAC Requires minimum 5 points')
return
# Obtain camera matrix and distortion coefficients
camera_matrix = CAMERA_MODEL.intrinsicMatrix()
dist_coeffs = CAMERA_MODEL.distortionCoeffs()
# Estimate extrinsics
success, rotation_vector, translation_vector, inliers = cv2.solvePnPRansac(points3D,
points2D, camera_matrix, dist_coeffs, flags=cv2.SOLVEPNP_ITERATIVE)
# Compute re-projection error.
points2D_reproj = cv2.projectPoints(points3D, rotation_vector,
translation_vector, camera_matrix, dist_coeffs)[0].squeeze(1)
assert(points2D_reproj.shape == points2D.shape)
error = (points2D_reproj - points2D)[inliers] # Compute error only over inliers.
rmse = np.sqrt(np.mean(error[:, 0] ** 2 + error[:, 1] ** 2))
rospy.loginfo('Re-projection error before LM refinement (RMSE) in px: ' + str(rmse))
# Refine estimate using LM
if not success:
rospy.logwarn('Initial estimation unsuccessful, skipping refinement')
elif not hasattr(cv2, 'solvePnPRefineLM'):
rospy.logwarn('solvePnPRefineLM requires OpenCV >= 4.1.1, skipping refinement')
else:
assert len(inliers) >= 3, 'LM refinement requires at least 3 inlier points'
rotation_vector, translation_vector = cv2.solvePnPRefineLM(points3D[inliers],
points2D[inliers], camera_matrix, dist_coeffs, rotation_vector, translation_vector)
# Compute re-projection error.
points2D_reproj = cv2.projectPoints(points3D, rotation_vector,
translation_vector, camera_matrix, dist_coeffs)[0].squeeze(1)
assert(points2D_reproj.shape == points2D.shape)
error = (points2D_reproj - points2D)[inliers] # Compute error only over inliers.
rmse = np.sqrt(np.mean(error[:, 0] ** 2 + error[:, 1] ** 2))
rospy.loginfo('Re-projection error after LM refinement (RMSE) in px: ' + str(rmse))
# Convert rotation vector
rotation_matrix = cv2.Rodrigues(rotation_vector)[0]
euler = euler_from_matrix(rotation_matrix)
# Save extrinsics
np.savez(os.path.join(folder, 'extrinsics.npz'),
euler=euler, R=rotation_matrix, T=translation_vector.T)
# Display results
print('Euler angles (RPY):', euler)
print('Rotation Matrix:', rotation_matrix)
print('Translation Offsets:', translation_vector.T)
'''
Projects the point cloud on to the image plane using the extrinsics
Inputs:
img_msg - [sensor_msgs/Image] - ROS sensor image message
velodyne - [sensor_msgs/PointCloud2] - ROS velodyne PCL2 message
image_pub - [sensor_msgs/Image] - ROS image publisher
Outputs:
Projected points published on /sensors/camera/camera_lidar topic
'''
def project_point_cloud(velodyne, img_msg, image_pub):
# Read image using CV bridge
try:
img = CV_BRIDGE.imgmsg_to_cv2(img_msg, 'bgr8')
except CvBridgeError as e:
rospy.logerr(e)
return
# Transform the point cloud
try:
transform = TF_BUFFER.lookup_transform('world', 'velodyne', rospy.Time())
velodyne = do_transform_cloud(velodyne, transform)
except tf2_ros.LookupException:
pass
# Extract points from message
points3D = ros_numpy.point_cloud2.pointcloud2_to_array(velodyne)
points3D = np.asarray(points3D.tolist())
# Group all beams together and pick the first 4 columns for X, Y, Z, intensity.
if OUSTER_LIDAR: points3D = points3D.reshape(-1, 9)[:, :4]
# Filter points in front of camera
inrange = np.where((points3D[:, 2] > 0) &
(points3D[:, 2] < 6) &
(np.abs(points3D[:, 0]) < 6) &
(np.abs(points3D[:, 1]) < 6))
max_intensity = np.max(points3D[:, -1])
points3D = points3D[inrange[0]]
# Color map for the points
cmap = matplotlib.cm.get_cmap('jet')
colors = cmap(points3D[:, -1] / max_intensity) * 255
# Project to 2D and filter points within image boundaries
points2D = [ CAMERA_MODEL.project3dToPixel(point) for point in points3D[:, :3] ]
points2D = np.asarray(points2D)
inrange = np.where((points2D[:, 0] >= 0) &
(points2D[:, 1] >= 0) &
(points2D[:, 0] < img.shape[1]) &
(points2D[:, 1] < img.shape[0]))
points2D = points2D[inrange[0]].round().astype('int')
# Draw the projected 2D points
for i in range(len(points2D)):
cv2.circle(img, tuple(points2D[i]), 2, tuple(colors[i]), -1)
# Publish the projected points image
try:
image_pub.publish(CV_BRIDGE.cv2_to_imgmsg(img, "bgr8"))
except CvBridgeError as e:
rospy.logerr(e)
'''
Callback function to publish project image and run calibration
Inputs:
image - [sensor_msgs/Image] - ROS sensor image message
camera_info - [sensor_msgs/CameraInfo] - ROS sensor camera info message
velodyne - [sensor_msgs/PointCloud2] - ROS velodyne PCL2 message
image_pub - [sensor_msgs/Image] - ROS image publisher
Outputs: None
'''
def callback(image, camera_info, velodyne, image_pub=None):
global CAMERA_MODEL, FIRST_TIME, PAUSE, TF_BUFFER, TF_LISTENER
# Setup the pinhole camera model
if FIRST_TIME:
FIRST_TIME = False
# Setup camera model
rospy.loginfo('Setting up camera model')
CAMERA_MODEL.fromCameraInfo(camera_info)
# TF listener
rospy.loginfo('Setting up static transform listener')
TF_BUFFER = tf2_ros.Buffer()
TF_LISTENER = tf2_ros.TransformListener(TF_BUFFER)
# Projection/display mode
if PROJECT_MODE:
project_point_cloud(velodyne, image, image_pub)
# Calibration mode
elif PAUSE:
# Create GUI processes
now = rospy.get_rostime()
img_p = multiprocessing.Process(target=extract_points_2D, args=[image, now])
pcl_p = multiprocessing.Process(target=extract_points_3D, args=[velodyne, now])
img_p.start(); pcl_p.start()
img_p.join(); pcl_p.join()
# Calibrate for existing corresponding points
calibrate()
# Resume listener
with KEY_LOCK: PAUSE = False
start_keyboard_handler()
'''
The main ROS node which handles the topics
Inputs:
camera_info - [str] - ROS sensor camera info topic
image_color - [str] - ROS sensor image topic
velodyne - [str] - ROS velodyne PCL2 topic
camera_lidar - [str] - ROS projected points image topic
Outputs: None
'''
def listener(camera_info, image_color, velodyne_points, camera_lidar=None):
# Start node
rospy.init_node('calibrate_camera_lidar', anonymous=True)
rospy.loginfo('Current PID: [%d]' % os.getpid())
rospy.loginfo('Projection mode: %s' % PROJECT_MODE)
rospy.loginfo('CameraInfo topic: %s' % camera_info)
rospy.loginfo('Image topic: %s' % image_color)
rospy.loginfo('PointCloud2 topic: %s' % velodyne_points)
rospy.loginfo('Output topic: %s' % camera_lidar)
# Subscribe to topics
info_sub = message_filters.Subscriber(camera_info, CameraInfo)
image_sub = message_filters.Subscriber(image_color, Image)
velodyne_sub = message_filters.Subscriber(velodyne_points, PointCloud2)
# Publish output topic
image_pub = None
if camera_lidar: image_pub = rospy.Publisher(camera_lidar, Image, queue_size=5)
# Synchronize the topics by time
ats = message_filters.ApproximateTimeSynchronizer(
[image_sub, info_sub, velodyne_sub], queue_size=5, slop=0.1)
ats.registerCallback(callback, image_pub)
# Keep python from exiting until this node is stopped
try:
rospy.spin()
except rospy.ROSInterruptException:
rospy.loginfo('Shutting down')
if __name__ == '__main__':
# Calibration mode, rosrun
if sys.argv[1] == '--calibrate':
camera_info = '/sensors/camera/camera_info'
image_color = '/sensors/camera/image_color'
velodyne_points = '/sensors/velodyne_points'
camera_lidar = None
PROJECT_MODE = False
# Projection mode, run from launch file
else:
camera_info = rospy.get_param('camera_info_topic')
image_color = rospy.get_param('image_color_topic')
velodyne_points = rospy.get_param('velodyne_points_topic')
camera_lidar = rospy.get_param('camera_lidar_topic')
PROJECT_MODE = bool(rospy.get_param('project_mode'))
# Start keyboard handler thread
if not PROJECT_MODE: start_keyboard_handler()
# Start subscriber
listener(camera_info, image_color, velodyne_points, camera_lidar)