拼接
重要
Download the example stitching Sample Data(示例数据) dataset and reference files to follow along or run the samples.
介绍
本文是关于如何拼接 Zivid 的无序点云的深入教程。
为了理解真正的问题,我们先来简单了解一下这个应用。与任何相机或人眼一样,Zivid 相机无法透视或绕过物体,它一次只能观察一侧。因此,要获得物体的完整 3D 模型,必须通过旋转物体或重新定位相机来从多个视角捕获它。
问题
Zivid SDK 返回的点云以 相机坐标系 表示,其中原点位于相机内部。从多个视角捕获时,每个点云都相对于捕获时相机的坐标系进行定义。如果只是简单地组合这些点云而不进行坐标系变换,它们将无法在空间上对齐,在 3D 空间中会显得脱节且不连贯。换句话说,这些点云并不共享与被扫描对象关联的通用坐标系。
解决方案
要将多个点云合并为对象的单个、空间对齐的 3D 表征,您需要:
将所有点云转换为附加在被扫描物体上的通用坐标系。
优化对齐以补偿位姿估计中的任何噪音或小错误。
从每个相机坐标系到公共坐标系的转换可以来自各种来源:机器人运动学、运动跟踪系统或手动测量。然而,这些转换很少是完美的,通常会引入微小的对齐误差。要纠正这些错误,您可以使用 Zivid::Experimental::Toolbox::localPointCloudRegistration()
。此 API 工具通过计算一个最佳地将一个点云配准到另一个点云的变换矩阵来优化两个重叠点云之间的对齐。
在开始拼接点云之前,务必确保捕获的点云具有足够多的重叠特征点。此外,我们还必须丢弃可能导致拼接错误的数据,例如距离相机太远的点,或者不属于我们正在拼接的物体/场景的点。我们建议在拼接前使用 Zivid 的 Region of Interest(感兴趣区域) 。对于相机静止的捕获,可以定义一个感兴趣区域,并将其用于所有捕获。当使用机械臂围绕物体移动相机时,可能需要为每个点云配置不同的感兴趣区域。
备注
Zivid 样本数据中所有需要拼接的点云均已经过 ROI 过滤。
无需预对准即可拼接点云
本节演示了如何在没有预对准的情况下拼接点云。关键要求是,物体与相机之间的相对运动在各个点云之间足够小,以确保每次捕获之间有明显的重叠。在本例中,物体保持静止,而相机在每次捕获之间略微移动,并通过 Zivid::Experimental::Toolbox::localPointCloudRegistration()
来对齐点云。我们先从一个简单的示例开始,该示例在没有先验位姿信息的情况下拼接两个点云,然后介绍一个更高级的案例,使用旋转台扫描整个物体。
拼接两个点云
这个简单示例演示了如何在没有预对齐的情况下拼接两个点云。要使用此方法进行拼接,我们需要:
加载两个 ZDF 文件。
将点云转换为无序格式。
应用体素下采样。
估计对齐的变换。
将点云拼接到一起。
对最终的拼接结果进行下采样。
下面演示了如何加载 ZDF 文件,并使用 Zivid::PointCloud::toUnorganizedPointCloud()
将点云转换为无序格式。多个无序点云使用 Zivid::UnorganizedPointCloud::extend()
来组合成一个 Zivid::UnorganizedPointCloud
对象,并显示出来。
// Ensure the dataset is extracted to the correct location depending on the operating system:
// - Windows: %ProgramData%/Zivid/StitchingPointClouds/
// - Linux: /usr/share/Zivid/data/StitchingPointClouds/
// StitchingPointClouds/
// └── BlueObject/
std::cout << "Reading point clouds from ZDF files" << std::endl;
const auto directory = std::filesystem::path(ZIVID_SAMPLE_DATA_DIR) / "StitchingPointClouds" / "BlueObject";
if(!std::filesystem::exists(directory))
{
std::ostringstream oss;
oss << "Missing dataset folders.\n"
<< "Make sure 'StitchingPointClouds/BlueObject/' exist at " << ZIVID_SAMPLE_DATA_DIR << ".\n\n"
<< "You can download the dataset (StitchingPointClouds.zip) from:\n"
<< "https://support.zivid.com/en/latest/api-reference/samples/sample-data.html";
throw std::runtime_error(oss.str());
}
const auto frame1 = Zivid::Frame((directory / "BlueObject.zdf").string());
const auto frame2 = Zivid::Frame((directory / "BlueObjectSlightlyMoved.zdf").string());
std::cout << "Converting organized point clouds to unorganized point clouds and voxel downsampling"
<< std::endl;
const auto unorganizedPointCloud1 = frame1.pointCloud().toUnorganizedPointCloud();
const auto unorganizedPointCloud2 = frame2.pointCloud().toUnorganizedPointCloud();
std::cout << "Displaying point clouds before stitching" << std::endl;
Zivid::UnorganizedPointCloud unorganizedNotStitchedPointCloud;
unorganizedNotStitchedPointCloud.extend(unorganizedPointCloud1);
unorganizedNotStitchedPointCloud.extend(unorganizedPointCloud2);
const auto unorganizedNotStitchedPointCloudOpen3D = copyToOpen3D(unorganizedNotStitchedPointCloud);
visualizePointCloud(unorganizedNotStitchedPointCloudOpen3D);
# Ensure the dataset is extracted to the correct location depending on the operating system:
# • Windows: %ProgramData%\\Zivid\\StitchingPointClouds\\
# • Linux: /usr/share/Zivid/data/StitchingPointClouds/
# The folder must contain:
# StitchingPointClouds/
# └── BlueObject/
print("Reading point clouds from files")
directory = get_sample_data_path() / "StitchingPointClouds" / "BlueObject"
if not directory.exists() or not directory.exists():
raise FileNotFoundError(
f"Missing dataset folders.\n"
f"Make sure 'StitchingPointClouds/BlueObject' exist at {get_sample_data_path()}.\n\n"
f"You can download the dataset (StitchingPointClouds.zip) from:\n"
f"https://support.zivid.com/en/latest/api-reference/samples/sample-data.html"
)
frame_1 = zivid.Frame(directory / "BlueObject.zdf")
frame_2 = zivid.Frame(directory / "BlueObjectSlightlyMoved.zdf")
print("Converting organized point clouds to unorganized point clouds and voxel downsampling")
unorganized_point_cloud_1 = frame_1.point_cloud().to_unorganized_point_cloud()
unorganized_point_cloud_2 = frame_2.point_cloud().to_unorganized_point_cloud()
print("Displaying point clouds before stitching")
unorganized_not_stitched_point_cloud = zivid.UnorganizedPointCloud()
unorganized_not_stitched_point_cloud.extend(unorganized_point_cloud_1)
unorganized_not_stitched_point_cloud.extend(unorganized_point_cloud_2)
display_pointcloud(
xyz=unorganized_not_stitched_point_cloud.copy_data("xyz"),
rgb=unorganized_not_stitched_point_cloud.copy_data("rgba")[:, 0:3],
)

应用体素下采样来减少点数,从而加快配准速度。然后,我们使用 Zivid::Experimental::Toolbox::localPointCloudRegistration()
计算两个点云之间的变换矩阵。使用得到的变换对第二个点云进行变换,并将其添加到最终点云(包含第一个点云的 Zivid::UnorganizedPointCloud
对象)。为了完成拼接,我们对拼接后的点云应用体素下采样,并显示结果。
std::cout << "Estimating transformation between point clouds" << std::endl;
const auto unorganizedPointCloud1LPCR = unorganizedPointCloud1.voxelDownsampled(1.0, 3);
const auto unorganizedPointCloud2LPCR = unorganizedPointCloud2.voxelDownsampled(1.0, 3);
const auto registrationParams = Zivid::Experimental::LocalPointCloudRegistrationParameters{};
const auto localPointCloudRegistrationResult = Zivid::Experimental::Toolbox::localPointCloudRegistration(
unorganizedPointCloud1LPCR, unorganizedPointCloud2LPCR, registrationParams);
if(!localPointCloudRegistrationResult.converged())
{
throw std::runtime_error("Registration did not converge...");
}
const auto pointCloud1ToPointCloud2Transform = localPointCloudRegistrationResult.transform();
std::cout << "Stitching and displaying point clouds" << std::endl;
Zivid::UnorganizedPointCloud finalPointCloud;
finalPointCloud.extend(unorganizedPointCloud1);
const auto unorganizedPointCloud2Transformed =
unorganizedPointCloud2.transformed(pointCloud1ToPointCloud2Transform.toMatrix());
finalPointCloud.extend(unorganizedPointCloud2Transformed);
const auto stitchedPointCloudOpen3D = copyToOpen3D(finalPointCloud);
visualizePointCloud(stitchedPointCloudOpen3D);
std::cout << "Voxel-downsampling the stitched point cloud" << std::endl;
finalPointCloud = finalPointCloud.voxelDownsampled(2.0, 1);
std::cout << "visualize the overllaped point clouds" << std::endl;
const auto stitchedDownampledPointCloudOpen3D = copyToOpen3D(finalPointCloud);
visualizePointCloud(stitchedDownampledPointCloudOpen3D);
print("Estimating transformation between point clouds")
unorganized_point_cloud_1_lpcr = unorganized_point_cloud_1.voxel_downsampled(voxel_size=1.0, min_points_per_voxel=3)
unorganized_point_cloud_2_lpcr = unorganized_point_cloud_2.voxel_downsampled(voxel_size=1.0, min_points_per_voxel=3)
registration_params = LocalPointCloudRegistrationParameters()
local_point_cloud_registration_result = local_point_cloud_registration(
target=unorganized_point_cloud_1_lpcr, source=unorganized_point_cloud_2_lpcr, parameters=registration_params
)
assert local_point_cloud_registration_result.converged(), "Registration did not converge..."
point_cloud_1_to_point_cloud_2_transform = local_point_cloud_registration_result.transform()
print("Displaying point clouds after stitching")
final_point_cloud = zivid.UnorganizedPointCloud()
final_point_cloud.extend(unorganized_point_cloud_1)
unorganized_point_cloud_2_transformed = unorganized_point_cloud_2.transformed(
point_cloud_1_to_point_cloud_2_transform.to_matrix()
)
final_point_cloud.extend(unorganized_point_cloud_2_transformed)
display_pointcloud(
xyz=final_point_cloud.copy_data("xyz"),
rgb=final_point_cloud.copy_data("rgba")[:, 0:3],
)
print("Voxel-downsampling the stitched point cloud")
final_point_cloud = final_point_cloud.voxel_downsampled(voxel_size=2.0, min_points_per_voxel=1)
display_pointcloud(
xyz=final_point_cloud.copy_data("xyz"),
rgb=final_point_cloud.copy_data("rgba")[:, 0:3],
)

使用旋转台进行拼接
此示例演示了如何拼接放置在旋转台上的物体的点云。要使用此方法进行拼接,我们需要:
连接到 Zivid 相机。
加载使用了感兴趣区域 (ROI) 的相机设置。
当物体旋转时捕获多个点云。
将每次捕获转换为无序的点云并进行下采样。
将新的 frame 注册到不断增长的模型中。
将不断增长的模型拼接到新的 frame 中。
进行下采样、显示结果并将最终结果导出为多边形文件格式 (.ply)。
备注
在此示例中,旋转台在约 25 秒内完成 360 度旋转。由于每个周期耗时超过 250 毫秒(包括捕获、传输、处理和拼接),我们在每次捕获之间添加了 1 秒的延迟。这样一来,我们便可以从物体周围均匀分布的角度进行约 20 次捕获。
我们首先连接相机,并加载一个包含已定义 ROI 的捕获设置。如前所述,ROI 的定义应包含转台上的物体。理想情况下,最好避免捕获转台本身的点,但如果物体足够大,通常也可以包含一些转台上的点。
接下来,我们需要捕获旋转物体的点云,并应用局部点云配准技术进行对齐。每个新捕捉到的点云都将成为参考 frame,之前拼接的模型将转换到该 frame 中。
为什么要转换拼接模型而不是最后一次捕获呢?因为将最后一次捕获的模型转换为固定的世界坐标系需要应用所有之前的转换,从而导致误差累积。通过始终将现有模型转换为最新的 frame,误差可以保持在局部范围内,更易于控制。
Zivid::UnorganizedPointCloud unorganizedStitchedPointCloud;
auto registrationParams = Zivid::Experimental::LocalPointCloudRegistrationParameters{};
auto previousToCurrentPointCloudTransform = Zivid::Matrix4x4::identity();
for(int numberOfCaptures = 0; numberOfCaptures < 20; ++numberOfCaptures)
{
std::this_thread::sleep_for(std::chrono::seconds(1));
auto frame = camera.capture2D3D(settings);
const auto unorganizedPointCloud = frame.pointCloud().toUnorganizedPointCloud().voxelDownsampled(1.0, 2);
if(numberOfCaptures != 0)
{
const auto registrationResult = Zivid::Experimental::Toolbox::localPointCloudRegistration(
unorganizedStitchedPointCloud,
unorganizedPointCloud,
registrationParams,
previousToCurrentPointCloudTransform);
if(!registrationResult.converged())
{
std::cout << "Registration did not converge..." << std::endl;
continue;
}
previousToCurrentPointCloudTransform = registrationResult.transform().toMatrix();
unorganizedStitchedPointCloud.transform(previousToCurrentPointCloudTransform.inverse());
}
unorganizedStitchedPointCloud.extend(unorganizedPointCloud);
std::cout << "Captures done: " << numberOfCaptures << std::endl;
}
std::cout << "Voxel-downsampling the stitched point cloud" << std::endl;
unorganizedStitchedPointCloud = unorganizedStitchedPointCloud.voxelDownsampled(0.75, 2);
const auto unorganizedStitchedPointCloudOpen3D = copyToOpen3D(unorganizedStitchedPointCloud);
visualizePointCloud(unorganizedStitchedPointCloudOpen3D);
previous_to_current_point_cloud_transform = np.eye(4)
unorganized_stitched_point_cloud = zivid.UnorganizedPointCloud()
registration_params = LocalPointCloudRegistrationParameters()
for number_of_captures in range(20):
time.sleep(1)
frame = camera.capture_2d_3d(settings)
unorganized_point_cloud = (
frame.point_cloud().to_unorganized_point_cloud().voxel_downsampled(voxel_size=1.0, min_points_per_voxel=2)
)
if number_of_captures != 0:
local_point_cloud_registration_result = local_point_cloud_registration(
target=unorganized_stitched_point_cloud,
source=unorganized_point_cloud,
parameters=registration_params,
initial_transform=previous_to_current_point_cloud_transform,
)
if not local_point_cloud_registration_result.converged():
print("Registration did not converge...")
continue
previous_to_current_point_cloud_transform = local_point_cloud_registration_result.transform().to_matrix()
unorganized_stitched_point_cloud.transform(np.linalg.inv(previous_to_current_point_cloud_transform))
unorganized_stitched_point_cloud.extend(unorganized_point_cloud)
print(f"Captures done: {number_of_captures}")
print("Voxel-downsampling the stitched point cloud")
unorganized_stitched_point_cloud = unorganized_stitched_point_cloud.voxel_downsampled(
voxel_size=0.75, min_points_per_voxel=2
)
display_pointcloud(
xyz=unorganized_stitched_point_cloud.copy_data("xyz"),
rgb=unorganized_stitched_point_cloud.copy_data("rgba")[:, 0:3],
)
备注
由于旋转台以恒定的角速度旋转,连续点云之间的变换应该相似。因此,可以将前一次的变换作为下一次配准的初始猜测。
最终,拼接结果会进一步进行体素下采样(voxel-downsampled)并显示。请参见下方的拼接点云结果。
Stitching point clouds with pre-alignment using a robot arm
This article outlines the process of stitching point clouds acquired from various robot-mounted camera positions, using hand-eye calibration data and local point cloud registration.
Overview and Requirements
This stitching method lets you generate a complete 3D point cloud of an object by moving a camera around it with a robot arm. It is especially useful when:
The object is larger than the camera’s field of view.
Capturing the object from multiple angles is needed for inspection, modeling, or manipulation.
To use this method, you need a valid hand-eye calibration result.
This is typically provided as hand_eye_transform.yaml
, which defines the transformation between the robot's end-effector coordinate system and the camera's coordinate system.
This transformation is used to relate captures made from different camera poses, allowing point clouds to be transformed into a common coordinate system for accurate alignment across multiple views.
You will need:
A set of captured Zivid point clouds (
capture_*.zdf
)A corresponding set of robot poses (
robot_pose_*.yaml
) — one per captureA
hand_eye_transform.yaml
obtained from a successful hand-eye calibration procedure
These elements together let you pre-align the individual captures in a common coordinate system.
Stitching Workflow
The stitching process follows these main steps:
Load multiple point clouds captured from different robot poses.
Load each pose (
robot_pose_*.yaml
) and the hand-eye calibration (hand_eye_transform.yaml
).Convert each robot pose into a camera pose using the hand-eye transform.
Pre-align the point clouds by transforming them from the camera's coordinate system to the robot's base coordinate system.
Downsample each point cloud (voxel grid) to speed up processing and reduce noise.
Use Local Point Cloud Registration to refine alignment between the growing stitched point cloud and each new point cloud.
Optionally re-load the original full-resolution clouds and apply the estimated transforms to stitch them in full resolution.
Export the final result as a stitched .ply point cloud.
[Robot Arm (Pose A)] -> capture_1.zdf
[Robot Arm (Pose B)] -> capture_2.zdf
...
[Robot Arm (Pose N)] -> capture_N.zdf
Each capture is paired with:
- robot_pose_*.yaml
- hand_eye_transform.yaml
Apply:
- Pre-alignment using robot pose and hand-eye calibration
- Local point cloud registration for refinement
Output:
- Combined and visualized point cloud
- Optionally reload original captures for full-resolution stitching
Export:
- Final stitched point cloud as a PLY file
How Local Registration Works
After initial pre-alignment using the robot and hand-eye poses, further refinement is needed to compensate for minor pose inaccuracies. Local Point Cloud Registration improves accuracy by aligning each downsampled point cloud with the growing point cloud (previously stitched point clouds).
Before applying registration, all point clouds are voxel-downsampled. This step is important for the stitching process, as it:
Reduces sensor noise, leading to more reliable alignments
Helps remove outliers, which could otherwise disrupt registration
Increase processing speed, by reducing the number of points without sacrificing structural detail
The user selects the stitching strategy before the process starts. However the actual stitching is performed only after all transformations are estimated:
Low-resolution stitching: Uses downsampled point clouds (as prepared during alignment).
High-resolution stitching: Reloads original full-resolution point clouds and applies the estimated transforms for a detailed final point cloud.
备注
Stitching without voxel downsampling (--full-resolution
) generates higher detail but requires more memory and computation time.
备注
When performing local registration, it’s important that point clouds are already reasonably well aligned from the pre-alignment step. If the initial misalignment is too large, the algorithm may fail to converge or produce inaccurate results.
The max_correspondence_distance
parameter defines the search radius for finding corresponding points between the source and target clouds.
It should be:
Larger than the typical point spacing (to allow correct matches)
But not so large that it includes incorrect correspondences, which can degrade alignment quality
Shown below are the stitched point cloud results for an object that required multiple captures because it was larger than the camera's field of view.
Zivid SDK Examples
Explore the full example code for stitching using a robot-mounted camera: