默认在主机上运行。在 RVC4 上,您可以通过
setRunOnHost(False) 将其卸载到设备。在 RVC2 上,仅支持主机端处理。添加于 DepthAI v3.6.0。如何放置
Python
Python
1import depthai as dai
2
3with dai.Pipeline() as pipeline:
4 pointCloud = pipeline.create(dai.node.PointCloud)输入和输出
passthroughDepth 会转发用于计算给定 PointCloudData 输出的原始深度帧。当输入队列非阻塞时很有用,并且您需要将深度帧与其对应的点云关联起来。配置
initialConfig 进行设置,或者在运行时通过 inputConfig 发送。在流式传输期间发送新配置是安全的——当配置、校准或帧转换发生变化时,节点会自动重新初始化。有关详细说明和用法示例,请参阅 PointCloudConfig。Python
Python
1pc = pipeline.create(dai.node.PointCloud)
2pc.initialConfig.setOrganized(True)
3pc.initialConfig.setLengthUnit(dai.LengthUnit.METER)
4pc.initialConfig.setTargetCoordinateSystem(dai.CameraBoardSocket.CAM_A)
5pc.setNumFramesPool(8)坐标系
ImgTransformation 外参中读取 T_frame_to_ref 并应用它,因此输出点云位于参考(原点)相机坐标系中。在此基础上,您可以应用以下三种附加转换之一:1. 相机插槽坐标系
CameraBoardSocket.CAM_A)。原点位于相机传感器处,旋转遵循相机的光学帧。节点使用设备校准自动计算外参转换。Python
1# 点云在彩色相机 (CAM_A) 的坐标系中
2pc.initialConfig.setTargetCoordinateSystem(dai.CameraBoardSocket.CAM_A)2. 外壳坐标系
Python
1# 点云在 VESA 安装坐标系中
2pc.initialConfig.setTargetCoordinateSystem(dai.HousingCoordinateSystem.VESA_A)HousingCoordinateSystem.CAM_A–CAM_D— 原点与CameraBoardSocket.CAM_A–CAM_D相同。区别在于旋转:X-Y 平面平行于设备的 front glass,而相机插槽坐标系则旋转到相机的光学帧。HousingCoordinateSystem.FRONT_CAM_A–FRONT_CAM_D— 位置与HousingCoordinateSystem.CAM_A–CAM_D类似,但向前移动到 front glass 的正面。HousingCoordinateSystem.VESA_A–VESA_J— 设备安装点。HousingCoordinateSystem.IMU— IMU 传感器原点。
3. 自定义转换矩阵
T_ref_to_custom——从参考相机到自定义坐标系的转换。节点将其与帧外参组合,得到最终应用的转换:Python
1# 90° rotation around Z axis
2transform = [
3 [0.0, -1.0, 0.0, 0.0],
4 [1.0, 0.0, 0.0, 0.0],
5 [0.0, 0.0, 1.0, 0.0],
6 [0.0, 0.0, 0.0, 1.0],
7]
8pc.initialConfig.setTransformationMatrix(transform)T_frame_to_ref的外部参数,将点转换到参考相机坐标系。选项之间的交互
CAMERA_SOCKET或HOUSING,分别对应这些模式,setTransformationMatrix的自定义变换矩阵将被忽略。仅当坐标系类型为DEFAULT(即未调用setTargetCoordinateSystem的任一重载)时,才会使用自定义矩阵。所有三种方法也可以直接在节点上调用(转发到initialConfig):Python
1pc.setTargetCoordinateSystem(dai.CameraBoardSocket.CAM_A)
2# or
3pc.setTargetCoordinateSystem(dai.HousingCoordinateSystem.VESA_A)用法
来自立体深度的点云
Python
Python
1import depthai as dai
2
3pipeline = dai.Pipeline()
4
5left = pipeline.create(dai.node.Camera).build(dai.CameraBoardSocket.CAM_B)
6right = pipeline.create(dai.node.Camera).build(dai.CameraBoardSocket.CAM_C)
7stereo = pipeline.create(dai.node.StereoDepth)
8left.requestOutput((640, 400)).link(stereo.left)
9right.requestOutput((640, 400)).link(stereo.right)
10
11pc = pipeline.create(dai.node.PointCloud)
12pc.initialConfig.setLengthUnit(dai.LengthUnit.METER)
13stereo.depth.link(pc.inputDepth)
14
15q = pc.outputPointCloud.createOutputQueue(maxSize=4, blocking=False)
16
17with pipeline:
18 pipeline.start()
19 while pipeline.isRunning():
20 pclData = q.get()
21 points = pclData.getPoints() # np.ndarray (N, 3) float32
22 print(f"Points: {len(points)}, Z=[{pclData.getMinZ():.2f}, {pclData.getMaxZ():.2f}]")彩色点云
Python
Python
1import depthai as dai
2
3pipeline = dai.Pipeline()
4
5left = pipeline.create(dai.node.Camera).build(dai.CameraBoardSocket.CAM_B)
6right = pipeline.create(dai.node.Camera).build(dai.CameraBoardSocket.CAM_C)
7color = pipeline.create(dai.node.Camera).build(dai.CameraBoardSocket.CAM_A)
8
9stereo = pipeline.create(dai.node.StereoDepth)
10left.requestFullResolutionOutput().link(stereo.left)
11right.requestFullResolutionOutput().link(stereo.right)
12
13colorOut = color.requestOutput((640, 400), type=dai.ImgFrame.Type.RGB888i,
14 resizeMode=dai.ImgResizeMode.CROP, enableUndistortion=True)
15
16pc = pipeline.create(dai.node.PointCloud)
17pc.initialConfig.setLengthUnit(dai.LengthUnit.METER)
18
19# Align depth to the color camera
20platform = pipeline.getDefaultDevice().getPlatform()
21if platform == dai.Platform.RVC4:
22 imageAlign = pipeline.create(dai.node.ImageAlign)
23 stereo.depth.link(imageAlign.input)
24 colorOut.link(imageAlign.inputAlignTo)
25 imageAlign.outputAligned.link(pc.inputDepth)
26else:
27 colorOut.link(stereo.inputAlignTo)
28 stereo.depth.link(pc.inputDepth)
29
30colorOut.link(pc.inputColor)
31
32q = pc.outputPointCloud.createOutputQueue(maxSize=4, blocking=False)
33
34with pipeline:
35 pipeline.start()
36 while pipeline.isRunning():
37 pcd = q.get()
38 if pcd.isColor():
39 xyz, rgba = pcd.getPointsRGB()
40 print(f"Points: {len(xyz)}, color=yes, Z=[{pcd.getMinZ():.2f}, {pcd.getMaxZ():.2f}]")示例
- PointCloud — 最小化的彩色点云示例。
- PointCloud Visualizer — 使用 Open3D 进行实时 3D 可视化。
- PointCloud Showcase — 展示了过滤、组织、坐标变换、自定义矩阵和彩色模式。
参考
class
dai::node::PointCloud
variable
std::shared_ptr< PointCloudConfig > initialConfig
Initial config to use when computing the point cloud.
variable
Input inputConfig
Input PointCloudConfig message with ability to modify parameters in runtime. Default queue is non-blocking with size 4.
variable
Subnode< node::Sync > sync
variable
InputMap & syncInputs
variable
Input & inputDepth
Input message with depth data used to create the point cloud. Routed through the internal Sync subnode.
variable
Output outputPointCloud
variable
Output passthroughDepth
Passthrough depth from which the point cloud was calculated. Suitable for when input queue is set to non-blocking behavior.
function
PointCloud()function
~PointCloud()function
Input & getColorInput()function
void setNumFramesPool(int numFramesPool)Specify number of frames in pool.
Parameters
- numFramesPool: How many frames should the pool have
function
void setRunOnHost(bool runOnHost)Specify whether to run on host or device By default, the node will run on host.
function
void useCPU()Use single-threaded CPU for processing
function
void useCPUMT(uint32_t numThreads)Use multi-threaded CPU for processing
function
void useGPU(uint32_t device)Use GPU for point cloud computation
Parameters
- device: GPU device index (default 0)
function
void setTargetCoordinateSystem(CameraBoardSocket targetCamera, bool useSpecTranslation)Set target coordinate system to transform point cloud
Parameters
- targetCamera: Target camera socket
- useSpecTranslation: Use spec translation instead of calibration (default: false)
function
void setTargetCoordinateSystem(HousingCoordinateSystem housingCS, bool useSpecTranslation)Set target coordinate system to housing coordinate system Point cloud will be transformed to this housing coordinate system
Parameters
- housingCS: Target housing coordinate system
- useSpecTranslation: Whether to use spec translation (default: true)
function
bool runOnHost()function
void buildInternal()class
dai::node::PointCloud::Impl
variable
LengthUnit targetLengthUnit
function
Impl()function
void setLogger(std::shared_ptr<::spdlog::logger > log)function
void computePointCloudDense(const uint8_t * depthData, std::vector< Point3f > & points)function
void computePointCloudDenseColored(const uint8_t * depthData, const uint8_t * colorData, std::vector< Point3fRGBA > & points)function
void applyTransformation(std::vector< PointT > & points)function
std::vector< PointT > filterValidPoints(const std::vector< PointT > & densePoints)function
void setLengthUnit(dai::LengthUnit lengthUnit)function
void useCPU()function
void useCPUMT(uint32_t numThreads)function
void useGPU(uint32_t device)function
void setIntrinsics(float fx, float fy, float cx, float cy, unsigned int width, unsigned int height)function
void setExtrinsics(const std::vector< std::vector< float >> & transformMatrix)function
void clearExtrinsics()需要帮助?
请前往 Discussion Forum 获取技术支持或提出您可能有的任何其他问题。