Timestamps

The O3R provides multiple timestamps that correspond to different times in the acquisition and processing of an image.

Acquisition timestamps

The acquisition timestamps refer to the center of each individual HDR exposure time (the O3R uses three exposures, a short, a medium, and a long, in that order). For the RGB image, there is only one exposure, so there is only one timestamp.

These timestamps can be retrieved with the ifm3d library respectively in the TOF_INFO or RGB_INFO buffers.

Receive timestamps

When a frame is received by the end device using the ifm3d API, a timestamp is attached to it (see frame documentation). Depending on the network configuration, the difference between the capture time and the reception time may vary. The ifm3d API appends a timestamp corresponding to the local time of the end device. If the ifm3d API runs on the VPU, the local CPU time of the VPU is used. If ifm3d API runs on the user’s machine, a different time zone may be used depending on the local time settings.

Note that NTP does not take time zones into account, but uses UTC as the reference for all timestamps. The user may need to convert the receive timestamps to UTC to match the NTP-synchronized capture timestamp.

The ifm3d API provides the timestamp of the frame as an array of two datetime objects. The second element of this table is inherited from legacy products that provided multiple timestamps. For the O3R, the user can use the first element of the table.

Synchronization

All timestamps can be synchronized using sNTP.

Example

The example below displays the acquisition and receive timestamps for 2D and 3D frames. It also shows timestamps when NTP synchronization is enabled: this relies on having a NTP server running on the user’s machine.

#############################################
# Copyright 2021-present ifm electronic, gmbh
# SPDX-License-Identifier: Apache-2.0
#############################################
# This examples shows how to retrieve image
# timestamps for the O3R.
# In a second part it inspects timestamps for
# a system synchronized with NTP. This relies
# on an internet connection on the local machine.

# Expected setup:
# RGB camera in port 0
# 3D camera in port 2
import time
import datetime

from ifm3dpy.device import O3R
from ifm3dpy.framegrabber import FrameGrabber, buffer_id
from ifm3dpy.deserialize import TOFInfoV4, RGBInfoV1

# IP configuration
LOCAL_IP = "192.168.0.111"  # Used for NTP synchronization
O3R_IP = "192.168.0.69"
# Change port numbers here for a different setup
PORT_2D = "port0"
PORT_3D = "port2"

o3r = O3R(O3R_IP)
PCIC_PORT_2D = o3r.get([f"/ports/{PORT_2D}/data/pcicTCPPort"])["ports"][PORT_2D][
    "data"
]["pcicTCPPort"]
PCIC_PORT_3D = o3r.get([f"/ports/{PORT_3D}/data/pcicTCPPort"])["ports"][PORT_3D][
    "data"
]["pcicTCPPort"]

fg_2d = FrameGrabber(o3r, pcic_port=PCIC_PORT_2D)
fg_3d = FrameGrabber(o3r, pcic_port=PCIC_PORT_3D)

epoch = datetime.datetime.utcfromtimestamp(0).astimezone(datetime.timezone.utc)
local_tz = datetime.datetime.now(datetime.timezone.utc).astimezone().tzinfo
print("All the timestamps are displayed in nanoseconds since epoch.")
print(f"Epoch date in UTC: {epoch}")
print(f"Local time zone: {local_tz}")
print("/////////////////////////////////")
####################
# For the 2D camera
####################
fg_2d.start([buffer_id.RGB_INFO])
[ok, frame] = fg_2d.wait_for_frame().wait_for(1000)

if not ok:
    raise RuntimeError("Timeout while waiting for a RGB_INFO.")

fg_2d.stop()

# Get the acquisition timestamps
rgb_info = RGBInfoV1().deserialize(frame.get_buffer(buffer_id.RGB_INFO))
# Convert frame datetime to timestamp since epoch
frame_ts = frame.timestamps()[0].timestamp()
# Display results
print(f"2D acquisition timestamp:           {rgb_info.timestamp_ns}")
print(f"2D receive timestamp:               {frame_ts*1e9:.0f}")
print(
    f"Acquisition to reception latency:   {abs(rgb_info.timestamp_ns - frame_ts*1e9):.0f}"
)

print("/////////////////////////////////")
####################
# For the 3D camera
####################
fg_3d.start([buffer_id.TOF_INFO])
[ok, frame] = fg_3d.wait_for_frame().wait_for(1000)

if not ok:
    raise RuntimeError("Timeout while waiting for a TOF_INFO.")

fg_3d.stop()
tof_info = TOFInfoV4().deserialize(frame.get_buffer(buffer_id.TOF_INFO))
frame_ts = frame.timestamps()[0].timestamp()
print(
    f"3D acquisition timestamps:                      {tof_info.exposure_timestamps_ns}"
)
print(f"3D reception timestamps:                        {frame_ts*1e9:.0f}")
print(
    f"Last exposure acquisition to reception latency: {abs(tof_info.exposure_timestamps_ns[0] - frame_ts*1e9):.0f}"
)

print("/////////////////////////////////")
##########################################
# Inspecting timestamps with sNTP enabled
##########################################
print("Enabling NTP synchronization on the device.")
print("Make sure you activate the NTP server on your local machine.")
o3r.set({"device": {"clock": {"sntp": {"availableServers": [f"{LOCAL_IP}"]}}}})
time.sleep(3)
curr_local_time = datetime.datetime.now().timestamp() * 1e9
curr_time_o3r = o3r.get(["/device/clock/currentTime"])["device"]["clock"]["currentTime"]
print(f"Current local timestamp:    {curr_local_time:.0f}")
print(f"Current time on device:     {int(curr_time_o3r)}")

fg_3d.start([buffer_id.TOF_INFO])
[ok, frame] = fg_3d.wait_for_frame().wait_for(1000)

if not ok:
    raise RuntimeError("Timeout while waiting for a TOF_INFO.")

fg_3d.stop()

tof_info = TOFInfoV4().deserialize(frame.get_buffer(buffer_id.TOF_INFO))
frame_ts = frame.timestamps()[0].timestamp()
print(
    f"3D acquisition timestamps (with sNTP):          {tof_info.exposure_timestamps_ns}"
)
print(f"3D reception timestamps (with sNTP):            {frame_ts*1e9:.0f}")
print(
    f"Last exposure acquisition to reception latency: {abs(tof_info.exposure_timestamps_ns[0] - frame_ts*1e9):.0f}"
)

Expected output:

$ python3 timestamps.py 
All the timestamps are displayed in nanoseconds since epoch.
Epoch date in UTC: 1970-01-01 05:00:00+00:00
Local time zone: EDT
/////////////////////////////////
2D acquisition timestamp:           1692812209955356240
2D receive timestamp:               1692812209955355904
Acquisition to reception latency:   256
/////////////////////////////////
3D acquisition timestamps:                      [1692812210115606937, 1692812210111675942, 1692812210098277180]
3D reception timestamps:                        1692812210115606016
Last exposure acquisition to reception latency: 1024
/////////////////////////////////
Enabling NTP synchronization on the device.
Make sure you activate the NTP server on your local machine.
Current local timestamp:    1692812213285470976
Current time on device:     1692812213291698338
3D acquisition timestamps (with sNTP):          [1692812213310297968, 1692812213306366973, 1692812213292968211]
3D reception timestamps (with sNTP):            1692812213310297088
Last exposure acquisition to reception latency: 768