realsense

Interface for pyrealsense2 API

class real_robot.utils.realsense.RSDevice(device_sn: str | None = None, uid: str | None = None, config: tuple[int, int, int] | dict[str, int | tuple[int, int, int]] | None = None, *, preset: str = 'Default', color_option_kwargs={}, depth_option_kwargs={}, json_file: str | Path | None = None, record_bag_path: str | Path | None = None, run_as_process: bool = False, parent_pose_so_name: str | None = None, local_pose: Pose = Pose([0, 0, 0], [0.5, 0.5, -0.5, 0.5]))[source]

Bases: object

RealSense Device. Depth stream will be aligned to camera color frame and resolution if Color stream is enabled.

For best depth accuracy with D435, set preset=”High Accuracy” and use (848, 480) depth resolution

References: * https://dev.intelrealsense.com/docs/d400-series-visual-presets * https://dev.intelrealsense.com/docs/tuning-depth-cameras-for-best-performance

get_intrinsic_matrix() ndarray | dict[str, ndarray][source]

Returns a 3x3 camera intrinsics matrix, available after self.start()

property is_running: bool

Returns whether the streaming pipeline is running

print_device_info() None[source]

Print device information (similar to running rs-enumerate-devices -c). This includes: supported_configs, all_intrinsics, all_extrinsics

Only prints information with self._default_stream_formats

static rs_extr2np(extrinsics: extrinsics) ndarray[source]

Converts rs.extrinsics to 4x4 np.ndaray

static rs_intr2np(intrinsics: intrinsics) ndarray[source]

Converts rs.intrinsics to 3x3 np.ndaray

run_as_process()[source]

Run RSDevice as a separate process

start() bool[source]

Start the streaming pipeline

stop() bool[source]

Stop the streaming pipeline

property supported_color_options: dict[int, option_range]
property supported_depth_options: dict[int, option_range]
property supported_depth_presets: list[str]
wait_for_frames() dict[str, ndarray][source]

Wait until a new set of frames becomes available. Each enabled stream in the pipeline is time-synchronized.

Return ret_frames:

dictionary {stream_name: np.ndarray}. Supported examples: * “Color”: color image, [H, W, 3] np.uint8 array * “Depth”: depth image, [H, W] np.uint16 array * “Infrared 1/2”: infrared image, [H, W] np.uint8 array

class real_robot.utils.realsense.RealSenseAPI(**kwargs)[source]

Bases: object

This API should only be used for testing, use sensors.Camera instead

capture() dict[str, ndarray] | list[dict[str, ndarray]][source]

Capture data from all _enabled_devices.

Return frame_dicts:

list of frame_dict, {stream_name: np.ndarray}. Supported examples: “Color”: color image, [H, W, 3] np.uint8 array “Depth”: depth image, [H, W] np.uint16 array “Infrared 1/2”: infrared image, [H, W] np.uint8 array

disable_all_devices()[source]
enable_all_devices()[source]
real_robot.utils.realsense.check_rs_product_support(name: str) str[source]

Check if the RealSense device is supported. Print warning otherwise

real_robot.utils.realsense.get_connected_rs_devices(device_sn: str | list[str] | None = None) list[str] | device | list[device][source]

Returns list of connected RealSense devices.

Parameters:

device_sn – list of serial numbers of devices to get. If not None, only return those devices in matching order. Else, return all connected devices’ serial number

Return devices:

list of rs.device if device_sn is not None: list of connected devices’ serial number if device_sn is None

real_robot.utils.realsense.get_default_stream_config(product_type: str) tuple[int, int, int] | dict[str, int | tuple[int, int, int]][source]

Get default sensor stream config (width, height, fps) depending on product_type

Parameters:

product_type – RS product type, one of SUPPORTED_RS_PRODUCTS

Returns:

default sensor stream config (acceptable by CameraConfig and RSDevice)