How to: receive an image

The primary objective of ifm3d is to make it as simple and performant as possible to acquire pixel data from an ifm 3D camera of the O3xxxx series. Additionally, the data should be encoded in a useful format for performing computer vision and/or robotics perception tasks. A typical ifm3d client program follows the structure of a control loop whereby images are continuously acquired from the camera and acted upon in some application-specific way.

At the end of this ‘how to’, you should be able to receive images and know the basic usage of the O3R, FrameGrabber and Frame classes.

Note: for O3D or O3X devices, simply use the O3D/O3X class in place of the O3R in the following code.

O3R, FrameGrabber and Frame

ifm3d provides three main classes:

  • O3R holds the configuration of the camera heads, handles the connection, etc;

  • FrameGrabber receives frames (images);

  • Frame stores the image buffers.

Instantiating these objects is as follows:

o3r = O3R()
fg = FrameGrabber(o3r, pcic_port=50012)

Note: The example above assumes that an O3R camera head is connected to the VPU at the physical port 2, which has the PCIC TCP port 50012. The PCIC TCP port number can be retrieved via o3r.get([f"/ports/portX/data/pcicTCPPort"]) with portX being a valid port (for example port0, port1, etc).

The O3R class, counter-intuitively, refers to the computing unit (the VPU). It inherits its name from previous ifm 3D devices that only used one camera, with no distinction between sensing and computing units. You can input:

  • ip: the IP address of the device;

  • xmlrpc_port: the XML_RPC port (it is fixed at the moment);

  • password: the password to connect to the device (unused for the O3R).

The FrameGrabber stores a reference to the passed in camera shared pointer and starts a worker thread to stream in pixel data from the device. Its inputs:

  • o3r: The O3R instance (the image processing platform) that handles the connection to the camera heads;

  • port: PCIC port number of the camera head to grab data from (not the physical port number);

Note: instantiating the objects is done the same way for any imager type (2D, 3D, different resolutions, etc).

Note that ifm3d encourages the use of std::shared_ptr as a means to manage the ownership and lifetimes of the core actors in an ifm3d program. Indeed, you will notice that there is no need to explicitly allocate and deallocate memory. To instantiate the ifm3d::O3R object (or ifm3d::O3D/ifm3d::O3X), a call to ifm3d::Device::MakeShared() is made, rather than calling std::make_shared directly. This wrapper function is used to handle direct hardware probing to determine the type of camera that is connected. For example, this may be an O3R, O3D303, O3X, or something else. Regardless, a std::shared_ptr is returned from this call.

Set the schema and start the FrameGrabber

To start the data stream, the Start function must be used. This Start needs a schema which is a std::vector<ifm3d::buffer_id> and contains the buffer_id of the data needed for the application:

fg.start([buffer_id.NORM_AMPLITUDE_IMAGE,buffer_id.RADIAL_DISTANCE_IMAGE,buffer_id.XYZ])

The device provides many types of buffers. All the buffers might not be required for application. Setting the schema provides a way to enable only buffer_ids required for the application. This also reduce the bandwidth required to get the data from the device.

Receive an image

Register a callback

The recommended way to receive a frame is to use the callback function. You can register a callback function that will be executed for every received frame, until the program exits.

def callback(frame):
    # Read the distance image and display a pixel in the center
    dist = frame.get_buffer(buffer_id.RADIAL_DISTANCE_IMAGE)
    (width, height) = dist.shape
    print(dist[width//2,height//2])
    pass

...
fg.start([buffer_id.RADIAL_DISTANCE_IMAGE])
fg.on_new_frame(callback)
...
fg.stop()

Alternatively: wait for a frame

You just need to call the WaitForFrame function. This Framegrabber method returns std::Future<ifm3d::Frame>. The Frame class stores all the received data. Make sure the camera head is in “RUN” mode.

frame = fg.wait_for_frame().wait() # wait without timeout
<!-- # OR -->
[ok, frame] = fg.wait_for_frame().wait_for(500) # wait with 500ms timeout
<!-- # OR -->
frame = await fg.wait_for_frame() # using asyncio

Access the data

Accessing the received data is done through the Frame. Different data types are available depending on whether the camera is a 2D or a 3D camera. Simply access the image by calling get_buffer passing the buffer_id of the required image as a parameter.

# For 3D data:
dist = frame.get_buffer(buffer_id.RADIAL_DISTANCE_IMAGE)
# For 2D data:
rgb = frame.get_buffer(buffer_id.JPEG_IMAGE)

The full example

Using a callback

import time
from ifm3dpy.device import O3R
from ifm3dpy.framegrabber import FrameGrabber, buffer_id


def callback(frame):
    # Read the distance image and display a pixel in the center
    dist = frame.get_buffer(buffer_id.RADIAL_DISTANCE_IMAGE)
    (width, height) = dist.shape
    print(dist[width // 2, height // 2])


# Initialize the objects
o3r = O3R()
fg = FrameGrabber(o3r, pcic_port=50012)

# set schema and start Grabber
fg.start(
    [buffer_id.NORM_AMPLITUDE_IMAGE, buffer_id.RADIAL_DISTANCE_IMAGE, buffer_id.XYZ]
)

fg.on_new_frame(callback)

# Sleep to avoid exiting the program too soon
time.sleep(1)

fg.stop()

Using the polling mode

from ifm3dpy.device import O3R
from ifm3dpy.framegrabber import FrameGrabber, buffer_id


def main():
    # Initialize the objects
    o3r = O3R()
    fg = FrameGrabber(o3r, pcic_port=50012)

    # Set schema and start Grabber
    fg.start(
        [buffer_id.NORM_AMPLITUDE_IMAGE, buffer_id.RADIAL_DISTANCE_IMAGE, buffer_id.XYZ]
    )

    # Get a frame
    [ok, frame] = fg.wait_for_frame().wait_for(1500)  # wait with 1500ms timeout

    # Check that a frame was received
    if not ok:
        raise RuntimeError("Timeout while waiting for a frame.")

    # Read the distance image and display a pixel in the center
    dist = frame.get_buffer(buffer_id.RADIAL_DISTANCE_IMAGE)
    (width, height) = dist.shape
    print(dist[width // 2, height // 2])
    fg.stop()


if __name__ == "__main__":
    main()