luxonis / depthai-core

DepthAI C++ Library
MIT License
238 stars 127 forks source link

Long exposure issues #555

Open 99991 opened 2 years ago

99991 commented 2 years ago

There a two issues with the exposure settings of the OAK-FCC-3P in conjunction with the Arducam HQ. Those issues hinder applications in astrophotography where very long exposure (several minutes to hours) are desirable. See for example this StackOverflow answer with a 42 minute long exposure using the RPI HQ camera.

  1. By default, the max exposure time is 33333 µs, i.e. $\frac{1}{30}$ seconds at a frame rate of 30 FPS. The max exposure time can be increased by lowering the frame rate. However, when setting the frame rate to 1 FPS, the max exposure is not 1000 ms, but rather somewhere between 600 and 700 ms.
  2. There is a huge delay between sending new exposure commands and actually receiving a change in brightness. My guess is that due to excessive buffering, it takes a certain number of frames for changes to propagate, which might be reasonable with high FPS, but at low FPS, waiting 5 seconds for a change is very slow.

For issue 1, it would be nice if the exposure time limit could be removed entirely.

For issue 2, it would be nice if the exposure settings could be applied more quickly -- perhaps after every frame? 600 ms should be more than enough time to transmit that information.

Here is a plot of exposure and corresponding brightness change where you can see both issues. For the first 5 seconds, the image brightness does not change because the exposure settings are slow to propagate. For the next 30ish seconds, the brightness does not change although the exposure is changed. After setting the exposure from 700 ms to 600 ms, the brightness finally changes, but the change again takes roughly 5 seconds to be applied.

annotated_plot

Here is the code I used to measure those values:

#!/usr/bin/env python3
import cv2
import numpy as np
import depthai as dai
import time

print("Usage:")
print("e: increase exposure")
print("r: decrease exposure")
print("i: increase iso")
print("o: decrease exposure")

fps = 1

# Maximum exposure is limited by frames per second
max_exposure_microseconds = int(1e6 / fps)

exposure_microseconds = max_exposure_microseconds

iso = 100

pipeline = dai.Pipeline()

cam = pipeline.createColorCamera()
cam.setResolution(dai.ColorCameraProperties.SensorResolution.THE_12_MP)

cam.setFps(fps)

xout_raw = pipeline.createXLinkOut()
xout_raw.setStreamName('raw')
cam.raw.link(xout_raw.input)

controlIn = pipeline.createXLinkIn()
controlIn.setStreamName('control')
controlIn.out.link(cam.inputControl)

device = dai.Device()
device.startPipeline(pipeline)

controlQueue = device.getInputQueue('control')

q = device.getOutputQueue(name='raw', maxSize=1, blocking=False)

def unpack_raw10(raw10):
    assert raw10.dtype == np.uint8 and len(raw10) % 5 == 0
    last_two_bits = raw10[4::5]

    r = np.zeros(len(raw10) * 4 // 5, dtype=np.uint16)

    r[0::4] = np.left_shift(raw10[0::5], 8, dtype=np.uint16) | ((last_two_bits & (0b11 << 0)) << 6)
    r[1::4] = np.left_shift(raw10[1::5], 8, dtype=np.uint16) | ((last_two_bits & (0b11 << 2)) << 4)
    r[2::4] = np.left_shift(raw10[2::5], 8, dtype=np.uint16) | ((last_two_bits & (0b11 << 4)) << 2)
    r[3::4] = np.left_shift(raw10[3::5], 8, dtype=np.uint16) | ((last_two_bits & (0b11 << 6))     )

    return r

print("Image mean color, Exposure, ISO, Elapsed time [sec]")

start_time = time.perf_counter()
for counter in range(10**10):
    ctrl = dai.CameraControl()
    ctrl.setManualExposure(exposure_microseconds, iso)
    controlQueue.send(ctrl)

    img_frame = q.get()

    width = img_frame.getWidth()
    height = img_frame.getHeight()

    bayer = unpack_raw10(img_frame.getData()).reshape(height, width)

    bgr = cv2.cvtColor(bayer, cv2.COLOR_BayerBG2BGR)

    elapsed_time = time.perf_counter() - start_time
    print(f'{bgr.mean():9.3f}, {exposure_microseconds:7d}, {iso:4d}, {elapsed_time:7.3f}')

    cv2.imshow("raw", cv2.resize(bgr, None, fx=0.25, fy=0.25))

    key = cv2.waitKey(1)

    if key == ord('e'): exposure_microseconds += 100_000
    if key == ord('r'): exposure_microseconds -= 100_000
    if key == ord('i'): iso += 100
    if key == ord('o'): iso -= 100
    if key == ord('q'): break

    exposure_microseconds = max(1, min(max_exposure_microseconds, exposure_microseconds))
    iso = max(100, min(1600, iso))
Luxonis-Brandon commented 2 years ago

Sorry for the trouble and thanks for the thorough details here! We're quite behind right now so just a candid heads up that it might be a bit before we can address this.

(And FWIW I personally quite want to see this application happen, will be super cool.)

rajsinghmn commented 1 year ago

@Luxonis-Brandon @99991 , I too am interested in the issue of having exposure settings propagated more quickly. Any luck/progress on this lately?

themarpe commented 1 year ago

@99991 @rajsinghmn

I think this can now be done by using "direct" set of commands, to manually control those parameters. These should skip over such delays, which become much more prominent with low framerates.

Let me know how this works for you

rajsinghmn commented 1 year ago

Thanks for the suggestion, @themarpe! Sorry, I'm fairly new to the luxonis platform. By "direct", do you mean using an alternative to XlinkIn for the exposure changes? Do you have a minimal example of how to directly control exposure?

themarpe commented 1 year ago

@rajsinghmn

Its on branch: camera_controls_misc

cam[c].initialControl.setMisc("manual-exposure-handling", "fast")

However, this only works for IMX378/IMX582 for now, so might not apply to your case as is...