How to: deserialize O3R data

Some of the data provided by the O3R platform needs to be deserialized to be used. This is the case for:

  • the intrinsic calibration parameters (ifm3dpy.deserialize.Calibration), which provides details like which optical model is used (Fisheye, pinhole) and the values for each of the model’s parameters,

  • the extrinsic calibration (optics to user) parameters ( ifm3dpy.deserialize.ExtrinsicOpticToUser), which provides the transformations between the optical system and the reference point on the camera housing,

  • the ODS zone information (ifm3dpy.deserialize.ODSInfoV1), which contains the zone id being used and the occupancy of the zones,

  • the ODS occupancy grid information (ifm3dpy.deserialize.ODSOccupancyGridV1), which contains occupancy grid data and the transformation matrix,

  • the RGB information (ifm3dpy.deserialize.RGBInfoV1), which provides exposure times and calibration parameters for the O3R RGB cameras.

For more information on the data structures of each buffer 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 RGBInfoV1 buffer.

#################################################################
# This examples shows how to use the deserializer module
# to extract data from the RGBInfoV1 buffer.
# The same principles can be applied to deserialize data from
# other buffers (see accompanying documentation for mode details)
#################################################################
# Import the relevant modules
from ifm3dpy.device import O3R
from ifm3dpy.framegrabber import FrameGrabber, buffer_id
from ifm3dpy.deserialize import RGBInfoV1

###########################
# Choose the IP and port number
###########################
IP = "192.168.0.69"
PORT = "port0"

###########################
# Create the O3R and FrameGrabber
# and choose which images
# to receive
###########################
o3r = O3R(IP)
# Assuming PORT is a 2D port
pcic_port = o3r.port(PORT).pcic_port
fg = FrameGrabber(cam=o3r, pcic_port=pcic_port)
# Define the images to receive when starting the data stream
fg.start([buffer_id.RGB_INFO])
try:
    # Get a frame
    [ok, frame] = fg.wait_for_frame().wait_for(500)
    # Retrieve the data from the relevant buffer
    if ok:
        rgb_info_buffer = frame.get_buffer(buffer_id.RGB_INFO)
    else:
        raise TimeoutError
except Exception as e:
    raise e
fg.stop()
###############################
# Extract data from the buffer
# Using the deserializer module
###############################
rgb_info = RGBInfoV1()
rgb_info_deser = rgb_info.deserialize(rgb_info_buffer)
print("Sample of data available in the RGBInfoV1 buffer:")
print(f"RGB info timestamp: {rgb_info_deser.timestamp_ns}")
print(f"Exposure time used for rgb images: {rgb_info_deser.exposure_time}")
print(
    f"RGB intrinsic calibration model id: {rgb_info_deser.intrinsic_calibration.model_id}"
)
print(
    f"RGB intrinsic calibration parameters: {rgb_info_deser.intrinsic_calibration.parameters}"
)