I am trying to test if my OAK-D camera is in sync with my host computer. I don't know how to access the UTC time of the camera to compare with my computer's UTC time. How can I check this? I want to save images based on my computer's time stamp not some deltatime of when the computer was turned on. I basically want to visualize what the figure on this page shows of all devices having the same time stamp (not some delta time): https://docs.luxonis.com/software/depthai-components/device/
OAK-D Camera Time Stamp not matching Host computer time
import datetime
import time
import depthai as dai
def main():
# 1. Capture "monotonic now" (time since host PC boot, unaffected by system clock changes)
monotonic_ref = dai.Clock.now() # Returns datetime.timedelta
# 2. Capture "UTC now" at the same instant
utc_ref = datetime.datetime.utcnow() # A naive datetime in UTC
# 3. Compute offset: (UTC time) - (monotonic time)
offset = utc_ref - monotonic_ref
print("Reference measure:")
print(f" Host monotonic: {monotonic_ref}")
print(f" UTC now: {utc_ref}")
print(f" => offset = {offset}")
# Example usage: convert future monotonic timestamps to UTC
print("\nWaiting 3 seconds to demonstrate future readings...\n")
time.sleep(3)
# Suppose we get a new monotonic timestamp
monotonic_now = dai.Clock.now()
# Convert monotonic -> UTC by adding offset
utc_now = monotonic_now + offset
print(f"Monotonic now: {monotonic_now}")
print(f"Approx UTC time: {utc_now}")
if __name__ == "__main__":
main()
- Edited
This makes much more sense, thank you! If I understand your code right, this is how I would compare the time stamp of an individual picture with my system time to check if they're in sync?
The output of this does say they're about 47 ms off though. Here's the output:
Camera Timestamp (UTC): 2025-01-08 17:53:53.251883+00:00
System Time (UTC): 2025-01-08 17:53:53.300047+00:00
Time Difference: 0.048164 seconds
WARNING: Timestamps are NOT synchronized!
import cv2
import numpy as np
import time
from datetime import datetime, timezone, timedelta
import depthai as dai
# OAK-D Thread
def oak_d_thread(pipeline):
# 1. Capture "monotonic now" (time since host PC boot, unaffected by system clock changes)
monotonic_ref = dai.Clock.now() # Returns datetime.timedelta
# 2. Capture "UTC now" at the same instant
utc_ref = datetime.now(timezone.utc) # A naive datetime in UTC
# 3. Compute offset: (UTC time) - (monotonic time)
offset = utc_ref - monotonic_ref
frame_cnt = 0
with dai.Device(pipeline) as device:
# # 1st value: Interval between timesync runs
# # 2nd value: Number of timesync samples per run which are used to compute a better value
# # 3rd value: If true partial timesync requests will be performed at random intervals, otherwise at fixed intervals
# device.setTimesync(timedelta(seconds=5), 10, True) # (These are default values)
q_rgb = device.getOutputQueue("rgb")
while True:
in_rgb = q_rgb.tryGet()
if in_rgb is not None:
frame = in_rgb.getCvFrame()
# cam_deltatime = dai.Clock.now() - in_rgb.getTimestamp()#.total_seconds()
cam_deltatime = in_rgb.getTimestamp()
cam_time = cam_deltatime + offset
system_time = datetime.now(timezone.utc)
# cam_time = datetime.fromtimestamp(timestamp, timezone.utc)
time_diff = (system_time - cam_time).total_seconds()
print(f"Camera Timestamp (UTC): {cam_time}")
print(f"System Time (UTC): {system_time}")
print(f"Time Difference: {time_diff:.6f} seconds")
if abs(time_diff) > 0.01: # Threshold of ±10 ms
print("\nWARNING: Timestamps are NOT synchronized!\n")
frame_cnt += 1
if frame_cnt > 10:
break
# Main Program
if __name__ == "__main__":
pipeline = dai.Pipeline()
cam_rgb = pipeline.createColorCamera()
cam_rgb.setBoardSocket(dai.CameraBoardSocket.CAM_A)
cam_rgb.setResolution(dai.ColorCameraProperties.SensorResolution.THE_1200_P)
cam_rgb.setPreviewSize(1024, 512)
cam_rgb.setInterleaved(False)
cam_rgb.setColorOrder(dai.ColorCameraProperties.ColorOrder.RGB)
xout_rgb = pipeline.createXLinkOut()
xout_rgb.setStreamName("rgb")
cam_rgb.preview.link(xout_rgb.input)
oak_d_thread(pipeline)
print("Finished processing OAK-D Camera data!")
crs287
The timestamps won't match because they are not taken at the same time. The 0.048s difference is due to latency. The timestamp is created when image exposure starts. The UTC timestamp of image is correct, just make sure you don't try to match it to system time when frame is received.
import cv2
import numpy as np
import time
from datetime import datetime, timezone, timedelta
import depthai as dai
# OAK-D Thread
def oak_d_thread(pipeline):
# 1. Capture "monotonic now" (time since host PC boot, unaffected by system clock changes)
monotonic_ref = dai.Clock.now() # Returns datetime.timedelta
# 2. Capture "UTC now" at the same instant
utc_ref = datetime.now(timezone.utc) # A naive datetime in UTC
# 3. Compute offset: (UTC time) - (monotonic time)
offset = utc_ref - monotonic_ref
frame_cnt = 0
with dai.Device(pipeline) as device:
# # 1st value: Interval between timesync runs
# # 2nd value: Number of timesync samples per run which are used to compute a better value
# # 3rd value: If true partial timesync requests will be performed at random intervals, otherwise at fixed intervals
# device.setTimesync(timedelta(seconds=5), 10, True) # (These are default values)
q_rgb = device.getOutputQueue("rgb")
while True:
in_rgb = q_rgb.tryGet()
if in_rgb is not None:
frame = in_rgb.getCvFrame()
# cam_deltatime = dai.Clock.now() - in_rgb.getTimestamp()#.total_seconds()
cam_deltatime = in_rgb.getTimestamp()
cam_time = cam_deltatime + offset
system_time = datetime.now(timezone.utc)
# cam_time = datetime.fromtimestamp(timestamp, timezone.utc)
time_diff = (system_time - cam_time).total_seconds()
print(f"Camera Timestamp (UTC): {cam_time}")
print(f"System Time (UTC): {system_time}")
print(f"Time Difference - latency: {time_diff:.6f} seconds")
print(f"Dai Clock converted to UTC: {dai.Clock.now() + offset}")
frame_cnt += 1
if frame_cnt > 10:
break
# Main Program
if __name__ == "__main__":
pipeline = dai.Pipeline()
cam_rgb = pipeline.createColorCamera()
cam_rgb.setBoardSocket(dai.CameraBoardSocket.CAM_A)
cam_rgb.setResolution(dai.ColorCameraProperties.SensorResolution.THE_1080_P)
cam_rgb.setPreviewSize(1024, 512)
cam_rgb.setInterleaved(False)
cam_rgb.setColorOrder(dai.ColorCameraProperties.ColorOrder.RGB)
xout_rgb = pipeline.createXLinkOut()
xout_rgb.setStreamName("rgb")
cam_rgb.preview.link(xout_rgb.input)
oak_d_thread(pipeline)
print("Finished processing OAK-D Camera data!")