Skip to content

RealSense: Capture Single Point Cloud

SUMMARY

Connect to a RealSense camera, capture a single colour-mapped point cloud, and visualise the 3D result in Rerun.

Example

Single point cloud capture output

Code

python
"""
A simple example demonstrating how to capture a single colour-mapped point
cloud from a RealSense camera and visualise it in Rerun.

Please run this example from a terminal to avoid issues with rerun's spawn mode.
"""

from loguru import logger

import rerun as rr

from telekinesis.medulla.cameras import realsense


def main():
    camera = realsense.RealSense(
        name="my_realsense",
    )
    try:
        rr.init("RealSense_Pointcloud_Example", spawn=True)
        rr.log("/", rr.ViewCoordinates.RDF, static=True)
        camera.connect()

        point_cloud = camera.capture_single_pointcloud()
        if point_cloud is None:
            logger.error("Failed to capture point cloud.")
            return

        rr.log(
            "Pointcloud_Capture",
            rr.Points3D(positions=point_cloud.positions, colors=point_cloud.colors),
        )
    except Exception as e:
        logger.error(
            f"Unable to capture point cloud. Caught exception: {type(e).__name__}: {e}"
        )
    finally:
        camera.disconnect()


if __name__ == "__main__":
    main()

Explanation

Now, let's break down the code piece by piece.

A RealSense camera object is created with just a name. No serial number is required — the class connects to the first available device automatically.

python
camera = realsense.RealSense(
    name="my_realsense",
)

Before connecting, the Rerun viewer is opened and a world coordinate frame is set. rr.ViewCoordinates.RDF declares Right-Down-Forward axes so Rerun renders the 3D scene with the correct orientation. Passing static=True logs this once and never repeats it on subsequent frames.

python
rr.init("RealSense_Pointcloud_Example", spawn=True)
rr.log("/", rr.ViewCoordinates.RDF, static=True)

camera.connect() initializes the RealSense pipeline with default stream settings, enabling both the depth and colour streams needed to build a colour-mapped point cloud.

python
camera.connect()

capture_single_pointcloud fuses one depth frame with one colour frame to produce a point cloud object. Its .positions attribute is an Nx3 float array of XYZ coordinates and its .colors attribute is an Nx3 uint8 array of per-point RGB values. The explicit None check handles the rare case where the depth-colour alignment fails to produce a valid frame.

python
point_cloud = camera.capture_single_pointcloud()
if point_cloud is None:
    logger.error("Failed to capture point cloud.")
    return

rr.Points3D logs the full coloured cloud to Rerun in a single call. No JPEG encoding is needed — positions and colours are passed as numeric arrays directly.

python
rr.log(
    "Pointcloud_Capture",
    rr.Points3D(positions=point_cloud.positions, colors=point_cloud.colors),
)

The finally block guarantees that camera.disconnect() is always called, stopping the RealSense pipeline and releasing all USB resources regardless of whether an exception occurred.

python
finally:
    camera.disconnect()

Run

bash
python capture_pointcloud_single_example.py

A Rerun viewer opens automatically. The colour-mapped point cloud appears under Pointcloud_Capture once acquisition completes.