2.2.1.5.1.1. calibration.lidar_camera_calibration package¶
2.2.1.5.1.1.1. Submodules¶
2.2.1.5.1.1.2. calibration.lidar_camera_calibration.calibrate_camera_lidar module¶
- calibration.lidar_camera_calibration.calibrate_camera_lidar.calibrate(ouster, image, queue)[source]¶
Calibrate the LiDAR and image points using OpenCV PnP RANSAC. Requires minimum 5 point correspondences.
- Parameters:
ouster – [sensor_msgs/PointCloud2] - ROS ouster PCL2 message
image – [numpy array] - image to display
queue – [multiprocessing.Queue] - queue to save the extrinsic matrix
- Returns:
None
- calibration.lidar_camera_calibration.calibrate_camera_lidar.callback(image, camera_info, ouster)[source]¶
Callback function to handle calibration and save new calibration matrix
- Parameters:
image – [sensor_msgs/Image] - ROS sensor image message
camera_info – [sensor_msgs/CameraInfo] - ROS sensor camera info message
ouster – [sensor_msgs/PointCloud2] - ROS ouster PCL2 message
- Returns:
None
- calibration.lidar_camera_calibration.calibrate_camera_lidar.extract_points_2D(disp, now)[source]¶
Runs the image point selection GUI process. Saves them in img_points.npy.
- Parameters:
disp – [numpy array] - image to display
now – [int] - ROS bag time in seconds
- Returns:
None
- calibration.lidar_camera_calibration.calibrate_camera_lidar.extract_points_3D(ouster, now)[source]¶
Runs the LiDAR point selection GUI process. Saves them in pcl_points.npy.
- Parameters:
ouster – [sensor_msgs/PointCloud2] - ROS ouster PCL2 message
now – [int] - ROS bag time in seconds
- Returns:
None
- calibration.lidar_camera_calibration.calibrate_camera_lidar.handle_keyboard()[source]¶
Handle keyboard interrupt to pause and pick points.
- Returns:
None
- calibration.lidar_camera_calibration.calibrate_camera_lidar.listener(camera_info, image_color, ouster_points)[source]¶
The main ROS node which handles the topics
- Parameters:
camera_info – [str] - ROS sensor camera info topic
image_color – [str] - ROS sensor image topic
ouster_points – [str] - ROS ouster PCL2 topic
- Returns:
None
- calibration.lidar_camera_calibration.calibrate_camera_lidar.plot_projected_calibration_points(points3D, rotation_vector, translation_vector, camera_matrix, image, color)[source]¶
Generates a plot with 3D points projected onto the image.
- Parameters:
points3D – [numpy array] - (N, 3) array of 3D points
rotation_vector – [numpy array] - (3, 1)
translation_vector – [numpy array] - (3, 1)
camera_matrix – [numpy array] - (3, 3) intrinsic camera matrix
image – [cv Mat] - camera image
color – [str] - color used for points
- Returns:
None
- calibration.lidar_camera_calibration.calibrate_camera_lidar.save_data(data, filename, folder, is_image=False)[source]¶
Save the point correspondences and image data. Points data will be appended if file already exists.
- Parameters:
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
- Returns:
None