Working with 3D point clouds is essential in robotics, autonomous vehicles, and 3D reconstruction for creating a comprehensive 3D environmental map and multi-sensor fusion. Often, we need to merge multiple scans and remove duplicate points for cleaner data.
This blog explains how to merge two LiDAR point clouds, one from the QT128 LiDAR and one from the OT128 LiDAR, using a rigid transformation calibration file.
In this tutorial, we'll explore how to:
Load and transform point clouds
Merge multiple scans
Remove duplicates using three different methods
Save and visualize the final result
We'll use Open3D, NumPy, and SciPy for efficient processing.
✔ How to load and transform point clouds using a JSON-defined transformation
✔ Techniques to merge two point clouds into one
✔ Three methods for duplicate removal:
Voxel Downsampling (fastest)
Exact Matching (strict)
Radius Filtering (most precise)
✔ How to save and visualize the final point cloud
3: By the end of this tutorial, you'll be able to:
✔ Load and transform point clouds between coordinate systems
✔ Merge multiple scans into a single point cloud
✔ Remove duplicate points efficiently
✔ Choose the best deduplication method for your use case
✔ Visualize and save the processed point cloud
Before starting, ensure you have:
Point cloud data files (PCD) from QT128 and OT128 LiDARs.
Calibration file calib_qt128_to_ot128.json describing the rigid transformation ( this file is generated here)
Python environment with these libraries installed:
open3d for point cloud processing.
numpy for matrix operations.
scipy for quaternion to rotation matrix conversion.
OT128 LiDAR point cloud: Reference point cloud (ot128.pcd).
QT128 LiDAR point cloud: Point cloud to be transformed (qt128.pcd).
Calibration JSON file: Contains translation and rotation parameters from QT128 frame to OT128 frame.
Load point clouds: Read both PCD files using Open3D.
Parse calibration JSON: Extract translation vector and quaternion rotation from the calibration file.
Compute transformation matrix: Convert quaternion to rotation matrix, build a 4x4 rigid transformation matrix.
Transform QT128 point cloud: Apply the transformation to align QT128 points into OT128 coordinate system.
Merge point clouds: Combine the transformed QT128 cloud with OT128 cloud.
Deduplicate the overlapping points in merged 3D cloud
Export and view the final result.
Output
Merged point cloud registered in OT128 coordinate system.
Visualization showing both LiDAR data combined in one frame.
The key to merging the two point clouds lies in the 'calib_qt128_to_ot128.json ' calibration file.
{
"00_date": "25/05/21-16:35:32",
"00_time_offset": 0,
"01_lidar_transform": {
"0_name": "QT128_to_OT128",
"1_model": "RigidTransform",
"2_extrinsicName": "LiDAR",
"3_description": "Transformation from QT128 to OT128 coordinate systems",
"4_extrinsic": {
"tx": 0.3662050080980058,
"ty": -2.588929256934579,
"tz": -1.3065719274452354,
"w": 0.9457254082981301,
"x": 0.2531310334834077,
"y": 0.047709545630156745,
"z": 0.19812100151856937
},
"4_extrinsic_projErr": 0.0
}
}
Translation (tx, ty, tz): How much to shift QT128 points in meters along X, Y, and Z axes to align with OT128.
Rotation (quaternion w, x, y, z): The 3D rotation needed to orient QT128 points to OT128 coordinate frame.
This is a rigid body transform (no scaling), mapping QT128 coordinates into OT128 frame.
How is this calibration file used?
This JSON file contains the rigid transformation parameters from the QT128 LiDAR sensor coordinate system to the OT128 sensor coordinate system.
The translation vector t=t = [tx, ty, tz]ᵀ moves points from QT128’s origin to OT128’s.
The rotation is stored as a quaternion q=[x,y,z,w], representing the 3D rotation needed to align the QT128 frame to OT128.
Our code reads these values, converts the quaternion to a rotation matrix, and constructs a 4×44 \times 44×4 transformation matrix TTT that can be applied to transform all points from the QT128 cloud into the OT128 frame.
7.0: Detailed Workflow
7.1.1: What will we do?
# Load calibration JSON file
with open("calib_qt128_to_ot128.json", "r") as f:
calib = json.load(f)
# Extract translation and quaternion rotation
extrinsic = data["01_lidar_transform"]["4_extrinsic"]
# Create 4x4 transformation matrix
quat = [extrinsic['x'], extrinsic['y'], extrinsic['z'], extrinsic['w']]
trans = [extrinsic['tx'], extrinsic['ty'], extrinsic['tz']]
rot = Rotation.from_quat(quat).as_matrix()
T = np.eye(4)
T[:3, :3] = rot
T[:3, 3] = trans
First, we open and parse the JSON file using Python’s built-in json library. The key "01_lidar_transform" contains the transformation data, and inside it, "4_extrinsic" holds the actual rotation and translation parameters.
The rotation is provided as a quaternion with components (x, y, z, w). We extract them into a list quat respecting the order that scipy.spatial.transform.Rotation expects: [x, y, z, w].
The translation vector is similarly extracted into a list trans.
Using Rotation.from_quat(quat).as_matrix(), we convert the quaternion into a 3×33 \times 33×3 rotation matrix.
Then, we create a 4×44 \times 44×4 identity matrix T. We set its top-left 3×33 \times 33×3 block to the rotation matrix and its top-right 3×13 \times 13×1 column to the translation vector, creating a homogeneous transformation matrix.
This matrix can now be used to transform points from the QT128 coordinate system into the OT128 system by matrix multiplication.
7.2.0 Step 2: Load and Transform Point Cloud
7.2.1: What will we do?
In the second step, we will load a .pcd point cloud file using Open3D, convert the points into homogeneous coordinates, apply the transformation matrix TTT computed in Step 1, and return a transformed point cloud.
pcd = o3d.io.read_point_cloud(pcd_path)
points = np.asarray(pcd.points)
# Convert to homogeneous coordinates
points_h = np.column_stack([points, np.ones(len(points))])
# Apply transformation
transformed_points = (transform @ points_h.T).T[:, :3]
# Create new point cloud
new_pcd = o3d.geometry.PointCloud()
new_pcd.points = o3d.utility.Vector3dVector(transformed_points)
if pcd.has_colors():
new_pcd.colors = pcd.colors
7.2.3: Breaking It Down: Line-by-Line Explanation
After importing Open3D library, as a powerful tool for 3D data processing, we use read_point_cloud function to load point cloud data from the .pcd file. This creates a point cloud object with an array of 3D points. This array contains the 3D coordinates of all points captured by each sensor.
Since transformation matrices work on homogeneous coordinates [x,y,z,1]T[x, y, z, 1]^T[x,y,z,1]T, we add a column of ones to our point array, making it an N×4N \times 4N×4 matrix where NNN is the number of points.
We multiply the 4×44 \times 44×4 transformation matrix with the transposed 4×N4 \times N4×N matrix of points to apply the rotation and translation. The result is transposed back to N×4N \times 4N×4, and we take only the first three columns [x,y,z][x, y, z][x,y,z] as the transformed 3D points.
We create a new Open3D point cloud to hold these transformed points. If the original point cloud had color data, we transfer it as well to preserve visualization fidelity.
7.3.1: What will we do?
We load the second .pcd file (in the OT128 coordinate system) as is, without applying any transformation since it is our reference frame.
7.3.2: Code Implementation
pcd_ot128 = o3d.io.read_point_cloud(pcd2_path)
7.3.3: Breaking It Down: Line-by-Line Explanation
This step is straightforward. We use Open3D's read_point_cloud to load the second point cloud directly.
7.4.1: What will we do?
We concatenate the transformed QT128 point cloud with the OT128 point cloud to form a merged point cloud.
7.4.2: Code Implementation
"""Merge two point clouds and print stats"""
points1 = np.asarray(pcd1.points)
points2 = np.asarray(pcd2.points)
merged_points = np.vstack([points1, points2])
merged_cld = o3d.geometry.PointCloud()
merged_cld.points = o3d.utility.Vector3dVector(merged_points)
if pcd1.has_colors() and pcd2.has_colors():
colors1 = np.asarray(pcd1.colors)
colors2 = np.asarray(pcd2.colors)
merged_colors = np.vstack([colors1, colors2])
merged_cld.colors = o3d.utility.Vector3dVector(merged_colors)
7.4.3: Breaking It Down: Line-by-Line Explanation
We convert the .points from both point clouds into NumPy arrays because NumPy is fast and easy for array operations like concatenation. pcd1.points and pcd2.points contain 3D coordinates (x, y, z) of each point. After that, we vertically stacks both arrays:points1, points2 to merge. Think of it as simply adding more rows to your existing list of 3D points. The merged_points now contains all points from both clouds. Then, we initialize an empty point cloud called merged_cld which will eventually contain all the combined points.Think of it as creating a blank canvas. After that, we assign the merged point data (stored in merged_points as a NumPy array) to the points property of an Open3D point cloud object (merged_cld). It transforms this raw data into a structured and functional point cloud that Open3D can work with as a 3D geometry object.Next, we handles the merging of color data when combining two point clouds, ensuring that visual information is preserved in the final merged cloud. The process begins with a check to confirm that both input point clouds contain color information using pcd1.has_colors() and pcd1.has_colors(). The pcd1.colors and pcd2.colors properties, which store the RGB values in Open3D's internal format, are converted into NumPy arrays using np.asarray(). This conversion allows for efficient manipulation of the color data using standard NumPy operations. The actual merging of colors happens through np.vstack([colors1, colors2]), which vertically stacks (combines row-wise) the color arrays from both point clouds. For example, if the first cloud has colors for 100 points and the second has colors for 150 points, the resulting merged color array will contain all 250 color values in sequence. This operation preserves the order of points, ensuring that the colors align correctly with the merged geometry. Finally, the merged color array is assigned back to the new point cloud object using o3d.utility.Vector3dVector(merged_colors). This crucial step converts the NumPy array back into Open3D's internal format, making the color data compatible with Open3D's visualization and processing functions. The Vector3dVector wrapper is essential because it maintains memory efficiency while providing the necessary interface for Open3D's C++ backend to work with the color data.
After merging, it is common to have overlapping or duplicate points. We will present three methods to remove duplicates or downsample the merged point cloud.
7.5.1: Method 1: Voxel Grid Filtering for Point Cloud Deduplication"
filtered_cld= cld.voxel_down_sample(voxel_size)
This method implements efficient point cloud deduplication through voxel grid downsampling using using Open3D's optimized voxel_down_sample() function. The technique partitions 3D space into uniform volumetric cells (voxels) of specified size (voxel_size), where all points within each voxel are consolidated to a single representative point. The voxel_size parameter serves as a spatial threshold - points closer than this distance are merged, making it ideal for removing duplicate measurements from overlapping scans.
7.5.2: Method 2: Tolerance-Controlled Coordinate Matching for Point Cloud Deduplication
# Snap points to nearest tolerance-aligned coordinates
rounded = np.round(points / tolerance) * tolerance
# Get indices of first unique points (discard values with _)
_, unique_indices = np.unique(rounded, axis=0, return_index=True)
# Create new point cloud with filtered points
filtered_pcd = o3d.geometry.PointCloud()
filtered_pcd.points = o3d.utility.Vector3dVector(points[unique_indices])
This method efficiently removes duplicate points from a point cloud through exact coordinate matching with configurable tolerance. By rounding coordinates to a user-defined tolerance (defaulting to 0.000001 meters) and applying NumPy's optimized unique() function, it identifies and eliminates redundant points while preserving the original order. The solution maintains color data integrity when present and generates helpful statistics about the filtering results. Its combination of precise control (via the tolerance parameter), computational efficiency (leveraging NumPy's vectorized operations), and data preservation makes it particularly valuable for processing merged 3D scans or cleaning sensor data where minor measurement variations might create artificial duplicates. The function returns a deduplicated point cloud ready for further analysis or visualization, complete with performance metrics about the cleaning process.
7.5.3: Method 3: "KDTree-Based Radius Filtering for Duplicate Removal
tree = o3d.geometry.KDTreeFlann(cld)
to_keep = []
for i in range(len(points)):
[k, idx, _] = tree.search_radius_vector_3d(cld.points[i], radius)
if i == idx[0]: # Only keep first point in neighborhood
to_keep.append(i)
This method removes duplicate points by analyzing local neighborhoods within a specified radius. For this, it builds o3d.geometry.KDTreeFlann(pcd)o enable fast neighborhood searches. For each point, it finds all neighbors within the specified radius using search_radius_vector_3d(). The first point in each neighborhood (if i == idx[0]) is kept while others are discarded, effectively removing nearby duplicates.
This tutorial demonstrated a complete pipeline for merging and deduplicating LiDAR point clouds from two sensors (QT128 and OT128) using Open3D. We covered:
Loading & Transforming Point Clouds: Applying a rigid transformation from calibration data.
Merging Scans: Combining two point clouds into a unified 3D representation.
Duplicate Removal: Comparing three methods—voxel grid filtering (fastest), exact coordinate matching (most precise), and radius-based filtering (balanced).
Each method offers unique trade-offs in speed, precision, and detail preservation, allowing you to choose the best approach based on your application.
Now that you have a fully operational pipeline for merging and cleaning LiDAR point clouds, the next phase is real-world deployment to capture high-quality 3D data.
Yongin-si, South Korea
sumairamanzoorpk@gmail.com