How to: deserialize O3R data

When you acquire a frame from a FrameGrabber instance, the contents of each buffer depend on its buffer_id.

  • Image buffers (e.g., RADIAL_DISTANCE_IMAGE, NORM_AMPLITUDE_IMAGE, CONFIDENCE_IMAGE, JPEG_IMAGE, XYZ) are delivered as numeric arrays (NumPy arrays in Python, std::vector/cv::Mat in C++). These can be used directly for computation and visualization.

  • Metadata buffers (e.g., TOF_INFO, RGB_INFO, O3R_ODS_INFO etc.,) are delivered as serialized structs. To access their fields, you must deserialize them using the appropriate deserialize class.

Buffer IDs with respective deserialize class

Buffer ID

Deserializer Class

Description

TOF_INFO

TofInfoV4

Metadata for ToF images: resolutions, exposures, timestamps, calibration, etc.

RGB_INFO

RGBInfoV1

Metadata for ToF images: resolutions, exposures, timestamps, calibration, etc.

O3R_ODS_INFO

ODSInfoV1

Zone ID and zone information for Object Detection.

O3R_ODS_OCCUPANCY_GRID

ODSOccupancyGridV1

Occupancy grid data with transformation matrix.

O3R_ODS_POLAR_OCC_GRID

ODSPolarOccupancyGridV1

A compressed version of the grid using polar coordinates

O3R_ODS_EXTRINSIC_CALIBRATION_CORRECTION

ODSExtrinsicCalibrationCorrectionV1

Extrinsic calibration correction parameters estimated by ODS application.

For more information on the available deserializer classes for managing different structs of other ifm devices like O3D, O3X, please refer to the Python API documentation or the C++ API documentation.

The usage of the deserializer is the same for all the buffers mentioned above: create the object, and call the deserialize function. Follow the example below for an example on deserializing the TOFInfoV4 buffer received from buffer_id - TOF_INFO.

# -*- coding: utf-8 -*-
#############################################
# Copyright 2024-present ifm electronic, gmbh
# SPDX-License-Identifier: Apache-2.0
#############################################
# This examples shows how to use the deserializer module
# to extract data from the TOFInfoV4 buffer.
#################################################################
# Import the relevant modules
from ifm3dpy.deserialize import TOFInfoV4
from ifm3dpy.device import O3R
from ifm3dpy.framegrabber import FrameGrabber, buffer_id


def main(IP: str) -> None:
    ###########################
    # Create the O3R and FrameGrabber
    # and choose which images to receive.
    # In this example we only receive one frame.
    ###########################
    o3r = O3R(IP)

    CONFIG = o3r.get()
    PCIC_PORT = None

    # Get the first available 3D port
    for port in o3r.ports():
        if port.type == "3D":
            # Get the first 3D port
            print(f"Using first available 3D Port {port.port}")
            PORT = port.port
            PCIC_PORT = port.pcic_port
            break

    if PORT is None:
        print("No 3D port found")
        return

    STATE = CONFIG["ports"][f"{PORT}"]["state"]
    if STATE != "RUN":
        print(f"Port {PORT} is in {STATE} state and not in RUN state")
        print("Set the camera RUN state")
        o3r.set({"ports": {f"{PORT}": {"state": "RUN"}}})

    fg = FrameGrabber(cam=o3r, pcic_port=PCIC_PORT)
    # Define the images to receive when starting the data stream
    fg.start([buffer_id.TOF_INFO])
    # Get a frame
    [ok, frame] = fg.wait_for_frame().wait_for(500)
    # Raise timeout error is not frame is received
    if not ok:
        raise TimeoutError(
            "No frame received, make sure the camera is not in ERROR state"
        )

    fg.stop()
    ###############################
    # Extract data from the buffer
    # Using the deserializer module
    ###############################
    tof_info = TOFInfoV4().deserialize(frame.get_buffer(buffer_id.TOF_INFO))
    print("Sample of data available in the TOFInfoV4 buffer:")
    print(f"Current minimum measurement range: {tof_info.measurement_range_min} m")
    print(f"Current maximum measurement range: {tof_info.measurement_range_max} m")
    print(f"Temperature of the illumination module: {tof_info.illu_temperature}")


if __name__ == "__main__":
    IP = "192.168.0.69"
    main(IP=IP)