realsense
RealSense RGB-D camera backend.
This module defines a RealSense RGB-D camera wrapper built on pyrealsense2.
It provides synchronized color and depth acquisition, optional point-cloud and confidence-map generation,
camera intrinsics access, and post-processing utilities such as depth alignment and hole filling.
The implementation exposes RealSense devices through the shared robotblockset RGB-D camera interface
for consistent use in perception and calibration pipelines.
Key functionalities include:
- RealSense device integration via the RGBDCamera interface.
- Configurable color/depth streaming resolution and frame rate.
- Synchronized RGB, depth, and optional confidence-map acquisition.
- Optional point-cloud generation from aligned depth and color data.
- Camera intrinsics retrieval from active device stream profiles.
- Depth post-processing support, including alignment and hole filling.
- class robotblockset.cameras.realsense.Realsense(resolution: Tuple[int, int] = (1920, 1080), fps: int = 30, enable_depth: bool = True, enable_pointcloud: bool = True, enable_confidence_map: bool = False, enable_hole_filling: bool = True, serial_number: str | None = None)[source]
Bases:
RGBDCameraWrapper around the pyrealsense2 library to use the RealSense cameras (tested for the D415 and D435).
Design decisions we made for this class: * Depth and color fps are the same * Depth resolution is automatically set * Depth frames are always aligned to color frames * Hole filling is enabled by default * Getting the confidence map is optional (disabled by default). The L515 supports a built-in confidence map, but the D415 and D435 do not. We do not support the L515 at this time.
Initialize a RealSense RGB-D camera wrapper.
- Parameters:
resolution (CameraResolutionType, optional) – CameraResolutionType, default=RESOLUTION_1080 Color stream resolution
(width, height)in pixels.fps (int, optional) – int, default=30 Target frame rate for color and depth streams.
enable_depth (bool, optional) – bool, default=True Enable depth acquisition.
enable_pointcloud (bool, optional) – bool, default=True Enable point-cloud computation from depth and color.
enable_confidence_map (bool, optional) – bool, default=False Enable confidence map computation based on stereo infrared frames.
enable_hole_filling (bool, optional) – bool, default=True Enable RealSense hole-filling post-processing on depth frames.
serial_number (str, optional) – Device serial number. If omitted, the default device is used.
- Raises:
ValueError – If point cloud or confidence map is enabled while depth is disabled.
RuntimeError – If pipeline startup fails due to invalid configuration or device issues.
- RESOLUTION_1080 = (1920, 1080)
- RESOLUTION_720 = (1280, 720)
- RESOLUTION_540 = (960, 540)
- RESOLUTION_480 = (848, 480)
- __init__(resolution: Tuple[int, int] = (1920, 1080), fps: int = 30, enable_depth: bool = True, enable_pointcloud: bool = True, enable_confidence_map: bool = False, enable_hole_filling: bool = True, serial_number: str | None = None) None[source]
Initialize a RealSense RGB-D camera wrapper.
- Parameters:
resolution (CameraResolutionType, optional) – CameraResolutionType, default=RESOLUTION_1080 Color stream resolution
(width, height)in pixels.fps (int, optional) – int, default=30 Target frame rate for color and depth streams.
enable_depth (bool, optional) – bool, default=True Enable depth acquisition.
enable_pointcloud (bool, optional) – bool, default=True Enable point-cloud computation from depth and color.
enable_confidence_map (bool, optional) – bool, default=False Enable confidence map computation based on stereo infrared frames.
enable_hole_filling (bool, optional) – bool, default=True Enable RealSense hole-filling post-processing on depth frames.
serial_number (str, optional) – Device serial number. If omitted, the default device is used.
- Raises:
ValueError – If point cloud or confidence map is enabled while depth is disabled.
RuntimeError – If pipeline startup fails due to invalid configuration or device issues.
- property fps: int
Return the configured camera frame rate.
- Returns:
Frame rate in frames per second.
- Return type:
int
- property resolution: Tuple[int, int]
Return the configured image resolution.
- Returns:
Resolution
(width, height)in pixels.- Return type:
CameraResolutionType
Classes
|
Wrapper around the pyrealsense2 library to use the RealSense cameras (tested for the D415 and D435). |