tici: improve AE (#21493)

* simplify histogram calculation

* add debug prints

* faster AE

* revert that

* lower log level

* use minimum recomended gains from datasheet

* use define

* fix min gain

* dynamic grey target

* fix build

* add low pass

* more stable rounding

* increase max gain

* always enable HCG

* correctly set min ev

* fix analog gain

* remove unused variable

* fix build

* move recomended gain into cost function

* tweak cost function a bit

* small LPF on desired ev

* fix typo

* lower ts

* clean up defines

* that was used in common

* add cast

* less cost is fine

* fix tests

* whitespace

* filtering is broken

* put back

* clip gain changes instead

* cost function tweaking

* Only go below recomended gain when absolutely necessary

* small penalty on changing gains
pull/21579/head
Willem Melching 4 years ago committed by GitHub
parent fd41e9f01b
commit 63c9b56063
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 35
      selfdrive/camerad/cameras/camera_common.cc
  2. 2
      selfdrive/camerad/cameras/camera_common.h
  3. 2
      selfdrive/camerad/cameras/camera_qcom.cc
  4. 185
      selfdrive/camerad/cameras/camera_qcom2.cc
  5. 21
      selfdrive/camerad/cameras/camera_qcom2.h
  6. 10
      selfdrive/camerad/cameras/real_debayer.cl
  7. 8
      selfdrive/camerad/test/ae_gray_test.cc
  8. 29
      selfdrive/camerad/test/ae_gray_test.h

@ -125,8 +125,6 @@ bool CameraBuf::acquire() {
const size_t globalWorkSize[] = {size_t(camera_state->ci.frame_width), size_t(camera_state->ci.frame_height)}; const size_t globalWorkSize[] = {size_t(camera_state->ci.frame_width), size_t(camera_state->ci.frame_height)};
const size_t localWorkSize[] = {DEBAYER_LOCAL_WORKSIZE, DEBAYER_LOCAL_WORKSIZE}; const size_t localWorkSize[] = {DEBAYER_LOCAL_WORKSIZE, DEBAYER_LOCAL_WORKSIZE};
CL_CHECK(clSetKernelArg(krnl_debayer, 2, localMemSize, 0)); CL_CHECK(clSetKernelArg(krnl_debayer, 2, localMemSize, 0));
int ggain = camera_state->analog_gain + 4*camera_state->dc_gain_enabled;
CL_CHECK(clSetKernelArg(krnl_debayer, 3, sizeof(int), &ggain));
CL_CHECK(clEnqueueNDRangeKernel(q, krnl_debayer, 2, NULL, globalWorkSize, localWorkSize, CL_CHECK(clEnqueueNDRangeKernel(q, krnl_debayer, 2, NULL, globalWorkSize, localWorkSize,
0, 0, &debayer_event)); 0, 0, &debayer_event));
#else #else
@ -278,39 +276,30 @@ static void publish_thumbnail(PubMaster *pm, const CameraBuf *b) {
free(thumbnail_buffer); free(thumbnail_buffer);
} }
float set_exposure_target(const CameraBuf *b, int x_start, int x_end, int x_skip, int y_start, int y_end, int y_skip, int analog_gain, bool hist_ceil, bool hl_weighted) { float set_exposure_target(const CameraBuf *b, int x_start, int x_end, int x_skip, int y_start, int y_end, int y_skip) {
const uint8_t *pix_ptr = b->cur_yuv_buf->y; int lum_med;
uint32_t lum_binning[256] = {0}; uint32_t lum_binning[256] = {0};
const uint8_t *pix_ptr = b->cur_yuv_buf->y;
unsigned int lum_total = 0; unsigned int lum_total = 0;
for (int y = y_start; y < y_end; y += y_skip) { for (int y = y_start; y < y_end; y += y_skip) {
for (int x = x_start; x < x_end; x += x_skip) { for (int x = x_start; x < x_end; x += x_skip) {
uint8_t lum = pix_ptr[(y * b->rgb_width) + x]; uint8_t lum = pix_ptr[(y * b->rgb_width) + x];
if (hist_ceil && lum < 80 && lum_binning[lum] > HISTO_CEIL_K * (y_end - y_start) * (x_end - x_start) / x_skip / y_skip / 256) {
continue;
}
lum_binning[lum]++; lum_binning[lum]++;
lum_total += 1; lum_total += 1;
} }
} }
// Find mean lumimance value
unsigned int lum_cur = 0; unsigned int lum_cur = 0;
int lum_med = 0;
int lum_med_alt = 0;
for (lum_med = 255; lum_med >= 0; lum_med--) { for (lum_med = 255; lum_med >= 0; lum_med--) {
lum_cur += lum_binning[lum_med]; lum_cur += lum_binning[lum_med];
if (hl_weighted) {
int lum_med_tmp = 0;
int hb = HLC_THRESH + (10 - analog_gain);
if (lum_cur > 0 && lum_med > hb) {
lum_med_tmp = (lum_med - hb) + 100;
}
lum_med_alt = lum_med_alt>lum_med_tmp?lum_med_alt:lum_med_tmp;
}
if (lum_cur >= lum_total / 2) { if (lum_cur >= lum_total / 2) {
break; break;
} }
} }
lum_med = lum_med_alt>0 ? lum_med + lum_med/32*lum_cur*abs(lum_med_alt - lum_med)/lum_total:lum_med;
return lum_med / 256.0; return lum_med / 256.0;
} }
@ -353,18 +342,12 @@ static void driver_cam_auto_exposure(CameraState *c, SubMaster &sm) {
struct ExpRect {int x1, x2, x_skip, y1, y2, y_skip;}; struct ExpRect {int x1, x2, x_skip, y1, y2, y_skip;};
const CameraBuf *b = &c->buf; const CameraBuf *b = &c->buf;
bool hist_ceil = false, hl_weighted = false;
int x_offset = 0, y_offset = 0; int x_offset = 0, y_offset = 0;
int frame_width = b->rgb_width, frame_height = b->rgb_height; int frame_width = b->rgb_width, frame_height = b->rgb_height;
#ifndef QCOM2
int analog_gain = -1;
#else
int analog_gain = c->analog_gain;
#endif
ExpRect def_rect; ExpRect def_rect;
if (Hardware::TICI()) { if (Hardware::TICI()) {
hist_ceil = hl_weighted = true;
x_offset = 630, y_offset = 156; x_offset = 630, y_offset = 156;
frame_width = 668, frame_height = frame_width / 1.33; frame_width = 668, frame_height = frame_width / 1.33;
def_rect = {96, 1832, 2, 242, 1148, 4}; def_rect = {96, 1832, 2, 242, 1148, 4};
@ -388,7 +371,7 @@ static void driver_cam_auto_exposure(CameraState *c, SubMaster &sm) {
} }
} }
camera_autoexposure(c, set_exposure_target(b, rect.x1, rect.x2, rect.x_skip, rect.y1, rect.y2, rect.y_skip, analog_gain, hist_ceil, hl_weighted)); camera_autoexposure(c, set_exposure_target(b, rect.x1, rect.x2, rect.x_skip, rect.y1, rect.y2, rect.y_skip));
} }
void common_process_driver_camera(SubMaster *sm, PubMaster *pm, CameraState *c, int cnt) { void common_process_driver_camera(SubMaster *sm, PubMaster *pm, CameraState *c, int cnt) {

@ -135,7 +135,7 @@ typedef void (*process_thread_cb)(MultiCameraState *s, CameraState *c, int cnt);
void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &frame_data); void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &frame_data);
kj::Array<uint8_t> get_frame_image(const CameraBuf *b); kj::Array<uint8_t> get_frame_image(const CameraBuf *b);
float set_exposure_target(const CameraBuf *b, int x_start, int x_end, int x_skip, int y_start, int y_end, int y_skip, int analog_gain, bool hist_ceil, bool hl_weighted); float set_exposure_target(const CameraBuf *b, int x_start, int x_end, int x_skip, int y_start, int y_end, int y_skip);
std::thread start_process_thread(MultiCameraState *cameras, CameraState *cs, process_thread_cb callback); std::thread start_process_thread(MultiCameraState *cameras, CameraState *cs, process_thread_cb callback);
void common_process_driver_camera(SubMaster *sm, PubMaster *pm, CameraState *c, int cnt); void common_process_driver_camera(SubMaster *sm, PubMaster *pm, CameraState *c, int cnt);

@ -1113,7 +1113,7 @@ void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) {
if (cnt % 3 == 0) { if (cnt % 3 == 0) {
const int x = 290, y = 322, width = 560, height = 314; const int x = 290, y = 322, width = 560, height = 314;
const int skip = 1; const int skip = 1;
camera_autoexposure(c, set_exposure_target(b, x, x + width, skip, y, y + height, skip, -1, false, false)); camera_autoexposure(c, set_exposure_target(b, x, x + width, skip, y, y + height, skip));
} }
} }

@ -22,18 +22,13 @@
#include "selfdrive/common/swaglog.h" #include "selfdrive/common/swaglog.h"
#include "selfdrive/camerad/cameras/sensor2_i2c.h" #include "selfdrive/camerad/cameras/sensor2_i2c.h"
#define FRAME_WIDTH 1928
#define FRAME_HEIGHT 1208
//#define FRAME_STRIDE 1936 // for 8 bit output
#define FRAME_STRIDE 2416 // for 10 bit output
//#define FRAME_STRIDE 1936 // for 8 bit output
#define MIPI_SETTLE_CNT 33 // Calculated by camera_freqs.py
extern ExitHandler do_exit; extern ExitHandler do_exit;
// global var for AE ops const size_t FRAME_WIDTH = 1928;
std::atomic<CameraExpInfo> cam_exp[3] = {{{0}}}; const size_t FRAME_HEIGHT =1208;
const size_t FRAME_STRIDE = 2416; // for 10 bit output
const int MIPI_SETTLE_CNT = 33; // Calculated by camera_freqs.py
CameraInfo cameras_supported[CAMERA_ID_MAX] = { CameraInfo cameras_supported[CAMERA_ID_MAX] = {
[CAMERA_ID_AR0231] = { [CAMERA_ID_AR0231] = {
@ -46,12 +41,25 @@ CameraInfo cameras_supported[CAMERA_ID_MAX] = {
}, },
}; };
float sensor_analog_gains[ANALOG_GAIN_MAX_IDX] = {3.0/6.0, 4.0/6.0, 4.0/5.0, 5.0/5.0, const bool enable_dc_gain = true;
5.0/4.0, 6.0/4.0, 6.0/3.0, 7.0/3.0, const float DC_GAIN = 2.5;
7.0/2.0, 8.0/2.0}; const float sensor_analog_gains[] = {
1.0/8.0, 2.0/8.0, 2.0/7.0, 3.0/7.0, // 0, 1, 2, 3
3.0/6.0, 4.0/6.0, 4.0/5.0, 5.0/5.0, // 4, 5, 6, 7
5.0/4.0, 6.0/4.0, 6.0/3.0, 7.0/3.0, // 8, 9, 10, 11
7.0/2.0, 8.0/2.0, 8.0/1.0}; // 12, 13, 14, 15 = bypass
// ************** low level camera helpers **************** const int ANALOG_GAIN_MIN_IDX = 0x0; // 0.125x
const int ANALOG_GAIN_REC_IDX = 0x7; // 1.0x
const int ANALOG_GAIN_MAX_IDX = 0xD; // 4.0x
const int EXPOSURE_TIME_MIN = 2; // with HDR, fastest ss
const int EXPOSURE_TIME_MAX = 1904; // with HDR, slowest ss
// global var for AE ops
std::atomic<CameraExpInfo> cam_exp[3] = {{{0}}};
// ************** low level camera helpers ****************
int cam_control(int fd, int op_code, void *handle, int size) { int cam_control(int fd, int op_code, void *handle, int size) {
struct cam_control camcontrol = {0}; struct cam_control camcontrol = {0};
camcontrol.op_code = op_code; camcontrol.op_code = op_code;
@ -521,14 +529,16 @@ static void camera_init(MultiCameraState *multi_cam_state, VisionIpcServer * v,
s->camera_num = camera_num; s->camera_num = camera_num;
s->dc_gain_enabled = false; s->dc_gain_enabled = false;
s->analog_gain = 0x5;
s->analog_gain_frac = sensor_analog_gains[s->analog_gain];
s->exposure_time = 256; s->exposure_time = 256;
s->exposure_time_max = 1.2 * EXPOSURE_TIME_MAX / 2;
s->exposure_time_min = 0.75 * EXPOSURE_TIME_MIN * 2;
s->request_id_last = 0; s->request_id_last = 0;
s->skipped = true; s->skipped = true;
s->ef_filtered = 1.0;
s->min_ev = EXPOSURE_TIME_MIN * sensor_analog_gains[ANALOG_GAIN_MIN_IDX] * (enable_dc_gain ? DC_GAIN : 1);
s->max_ev = EXPOSURE_TIME_MAX * sensor_analog_gains[ANALOG_GAIN_MAX_IDX] * DC_GAIN;
s->cur_ev = (s->max_ev - s->min_ev) / 2;
s->target_grey_fraction = 0.3;
s->gain_idx = ANALOG_GAIN_MIN_IDX;
s->buf.init(device_id, ctx, s, v, FRAME_BUF_COUNT, rgb_type, yuv_type); s->buf.init(device_id, ctx, s, v, FRAME_BUF_COUNT, rgb_type, yuv_type);
} }
@ -905,7 +915,7 @@ void handle_camera_event(CameraState *s, void *evdat) {
meta_data.frame_id = main_id - s->idx_offset; meta_data.frame_id = main_id - s->idx_offset;
meta_data.timestamp_sof = timestamp; meta_data.timestamp_sof = timestamp;
s->exp_lock.lock(); s->exp_lock.lock();
meta_data.gain = s->dc_gain_enabled ? s->analog_gain_frac * 2.5 : s->analog_gain_frac; meta_data.gain = s->dc_gain_enabled ? s->analog_gain_frac * DC_GAIN : s->analog_gain_frac;
meta_data.high_conversion_gain = s->dc_gain_enabled; meta_data.high_conversion_gain = s->dc_gain_enabled;
meta_data.integ_lines = s->exposure_time; meta_data.integ_lines = s->exposure_time;
meta_data.measured_grey_fraction = s->measured_grey_fraction; meta_data.measured_grey_fraction = s->measured_grey_fraction;
@ -925,100 +935,75 @@ void handle_camera_event(CameraState *s, void *evdat) {
} }
} }
// ******************* exposure control helpers ******************* static void set_camera_exposure(CameraState *s, float grey_frac) {
const float dt = 0.15;
void set_exposure_time_bounds(CameraState *s) { const float ts_grey = 10.0;
switch (s->analog_gain) { const float ts_ev = 0.05;
case 0: {
s->exposure_time_min = EXPOSURE_TIME_MIN;
s->exposure_time_max = EXPOSURE_TIME_MAX; // EXPOSURE_TIME_MIN * 4;
break;
}
case ANALOG_GAIN_MAX_IDX - 1: {
s->exposure_time_min = EXPOSURE_TIME_MIN; // EXPOSURE_TIME_MAX / 4;
s->exposure_time_max = EXPOSURE_TIME_MAX;
break;
}
default: {
// finetune margins on both ends
float k_up = sensor_analog_gains[s->analog_gain+1] / sensor_analog_gains[s->analog_gain];
float k_down = sensor_analog_gains[s->analog_gain-1] / sensor_analog_gains[s->analog_gain];
s->exposure_time_min = k_down * EXPOSURE_TIME_MIN * 2;
s->exposure_time_max = k_up * EXPOSURE_TIME_MAX / 2;
}
}
}
void switch_conversion_gain(CameraState *s) { const float k_grey = (dt / ts_grey) / (1.0 + dt / ts_grey);
if (!s->dc_gain_enabled) { const float k_ev = (dt / ts_ev) / (1.0 + dt / ts_ev);
s->dc_gain_enabled = true;
s->analog_gain -= 4;
} else {
s->dc_gain_enabled = false;
s->analog_gain += 4;
}
}
static void set_camera_exposure(CameraState *s, float grey_frac) { // Scale target grey between 0.2 and 0.4 depending on lighting conditions
// TODO: get stats from sensor? float new_target_grey = std::clamp(0.4 - 0.2 * log2(1.0 + s->cur_ev) / log2(6000.0), 0.2, 0.4);
float target_grey = 0.4 - ((float)(s->analog_gain + 4*s->dc_gain_enabled) / 48.0f); float target_grey = (1.0 - k_grey) * s->target_grey_fraction + k_grey * new_target_grey;
float exposure_factor = 1 + 30 * pow((target_grey - grey_frac), 3);
exposure_factor = std::max(exposure_factor, 0.56f);
if (s->camera_num != 1) {
s->ef_filtered = (1 - EF_LOWPASS_K) * s->ef_filtered + EF_LOWPASS_K * exposure_factor;
exposure_factor = s->ef_filtered;
}
s->exp_lock.lock(); float desired_ev = std::clamp(s->cur_ev * target_grey / grey_frac, s->min_ev, s->max_ev);
s->measured_grey_fraction = grey_frac; desired_ev = (1.0 - k_ev) * s->cur_ev + k_ev * desired_ev;
s->target_grey_fraction = target_grey;
// always prioritize exposure time adjust float best_ev_score = 1e6;
s->exposure_time *= exposure_factor; int new_g = 0;
int new_t = 0;
// switch gain if max/min exposure time is reached // Simple brute force optimizer to choose sensor parameters
// or always switch down to a lower gain when possible // to reach desired EV
bool kd = false; for (int g = ANALOG_GAIN_MIN_IDX; g <= ANALOG_GAIN_MAX_IDX; g++) {
if (s->analog_gain > 0) { float gain = sensor_analog_gains[g] * (enable_dc_gain ? DC_GAIN : 1);
kd = 1.1 * s->exposure_time / (sensor_analog_gains[s->analog_gain-1] / sensor_analog_gains[s->analog_gain]) < EXPOSURE_TIME_MAX / 2;
}
if (s->exposure_time > s->exposure_time_max) { // Compute optimal time for given gain
if (s->analog_gain < ANALOG_GAIN_MAX_IDX - 1) { int t = std::clamp(int(std::round(desired_ev / gain)), EXPOSURE_TIME_MIN, EXPOSURE_TIME_MAX);
s->exposure_time = EXPOSURE_TIME_MAX / 2;
s->analog_gain += 1; // Only go below recomended gain when absolutely necessary to not overexpose
if (!s->dc_gain_enabled && sensor_analog_gains[s->analog_gain] >= 4.0) { // switch to HCG // behavior is not completely linear causing visible step changes when switching gain
switch_conversion_gain(s); if (g < ANALOG_GAIN_REC_IDX && t > 10) {
} continue;
set_exposure_time_bounds(s);
} else {
s->exposure_time = s->exposure_time_max;
}
} else if (s->exposure_time < s->exposure_time_min || kd) {
if (s->analog_gain > 0) {
s->exposure_time = std::max(EXPOSURE_TIME_MIN * 2, (int)(s->exposure_time / (sensor_analog_gains[s->analog_gain-1] / sensor_analog_gains[s->analog_gain])));
s->analog_gain -= 1;
if (s->dc_gain_enabled && sensor_analog_gains[s->analog_gain] <= 1.25) { // switch back to LCG
switch_conversion_gain(s);
} }
set_exposure_time_bounds(s);
} else { // Compute error to desired ev
s->exposure_time = s->exposure_time_min; float score = std::abs(desired_ev - (t * gain)) * 10;
// Going below recomended gain needs lower penalty to not overexpose
float m = g > ANALOG_GAIN_REC_IDX ? 5.0 : 1.0;
score += std::abs(g - (int)ANALOG_GAIN_REC_IDX) * m;
// Small penalty on changing gain
score += std::abs(g - s->gain_idx);
if (score < best_ev_score) {
new_t = t;
new_g = g;
best_ev_score = score;
} }
} }
// set up config s->exp_lock.lock();
uint16_t AG = s->analog_gain + 4;
AG = 0xFF00 + AG * 16 + AG; s->measured_grey_fraction = grey_frac;
s->analog_gain_frac = sensor_analog_gains[s->analog_gain]; s->target_grey_fraction = target_grey;
s->analog_gain_frac = sensor_analog_gains[new_g];
s->gain_idx = new_g;
s->exposure_time = new_t;
s->dc_gain_enabled = enable_dc_gain;
float gain = s->analog_gain_frac * (s->dc_gain_enabled ? DC_GAIN : 1.0);
s->cur_ev = s->exposure_time * gain;
s->exp_lock.unlock(); s->exp_lock.unlock();
// printf("cam %d, min %d, max %d \n", s->camera_num, s->exposure_time_min, s->exposure_time_max);
// printf("cam %d, set AG to 0x%X, S to %d, dc %d \n", s->camera_num, AG, s->exposure_time, s->dc_gain_enabled);
uint16_t analog_gain_reg = 0xFF00 | (new_g << 4) | new_g;
struct i2c_random_wr_payload exp_reg_array[] = { struct i2c_random_wr_payload exp_reg_array[] = {
{0x3366, AG}, // analog gain {0x3366, analog_gain_reg}, // analog gain
{0x3362, (uint16_t)(s->dc_gain_enabled ? 0x1 : 0x0)}, // DC_GAIN {0x3362, (uint16_t)(s->dc_gain_enabled ? 0x1 : 0x0)}, // DC_GAIN
{0x305A, 0x00F8}, // red gain {0x305A, 0x00F8}, // red gain
{0x3058, 0x0122}, // blue gain {0x3058, 0x0122}, // blue gain
@ -1081,7 +1066,7 @@ void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) {
if (cnt % 3 == 0) { if (cnt % 3 == 0) {
const auto [x, y, w, h] = (c == &s->wide_road_cam) ? std::tuple(96, 250, 1734, 524) : std::tuple(96, 160, 1734, 986); const auto [x, y, w, h] = (c == &s->wide_road_cam) ? std::tuple(96, 250, 1734, 524) : std::tuple(96, 160, 1734, 986);
const int skip = 2; const int skip = 2;
camera_autoexposure(c, set_exposure_target(b, x, x + w, skip, y, y + h, skip, (int)c->analog_gain, true, true)); camera_autoexposure(c, set_exposure_target(b, x, x + w, skip, y, y + h, skip));
} }
} }

@ -10,30 +10,23 @@
#include "selfdrive/common/util.h" #include "selfdrive/common/util.h"
#define FRAME_BUF_COUNT 4 #define FRAME_BUF_COUNT 4
#define ANALOG_GAIN_MAX_IDX 10 // 0xF is bypass
#define EXPOSURE_TIME_MIN 2 // with HDR, fastest ss
#define EXPOSURE_TIME_MAX 1904 // with HDR, slowest ss
#define EF_LOWPASS_K 0.35
#define DEBAYER_LOCAL_WORKSIZE 16 #define DEBAYER_LOCAL_WORKSIZE 16
typedef struct CameraState { typedef struct CameraState {
MultiCameraState *multi_cam_state; MultiCameraState *multi_cam_state;
CameraInfo ci; CameraInfo ci;
std::mutex exp_lock; std::mutex exp_lock;
float analog_gain_frac;
uint16_t analog_gain;
bool dc_gain_enabled;
int exposure_time; int exposure_time;
int exposure_time_min; bool dc_gain_enabled;
int exposure_time_max; float analog_gain_frac;
float ef_filtered;
float cur_ev;
float min_ev, max_ev;
float measured_grey_fraction; float measured_grey_fraction;
float target_grey_fraction; float target_grey_fraction;
int gain_idx;
unique_fd sensor_fd; unique_fd sensor_fd;
unique_fd csiphy_fd; unique_fd csiphy_fd;

@ -26,9 +26,9 @@ half mf(half x, half cp) {
} }
} }
half3 color_correct(half3 rgb, int ggain) { half3 color_correct(half3 rgb) {
half3 ret = (0,0,0); half3 ret = (0,0,0);
half cpx = 0.01; //clamp(0.01h, 0.05h, cpxb + cpxk * min(10, ggain)); half cpx = 0.01;
ret += (half)rgb.x * color_correction[0]; ret += (half)rgb.x * color_correction[0];
ret += (half)rgb.y * color_correction[1]; ret += (half)rgb.y * color_correction[1];
ret += (half)rgb.z * color_correction[2]; ret += (half)rgb.z * color_correction[2];
@ -89,8 +89,7 @@ half phi(half x) {
__kernel void debayer10(const __global uchar * in, __kernel void debayer10(const __global uchar * in,
__global uchar * out, __global uchar * out,
__local half * cached, __local half * cached
uint ggain
) )
{ {
const int x_global = get_global_id(0); const int x_global = get_global_id(0);
@ -200,10 +199,9 @@ __kernel void debayer10(const __global uchar * in,
} }
rgb = clamp(0.0h, 1.0h, rgb); rgb = clamp(0.0h, 1.0h, rgb);
rgb = color_correct(rgb, (int)ggain); rgb = color_correct(rgb);
out[out_idx + 0] = (uchar)(rgb.z); out[out_idx + 0] = (uchar)(rgb.z);
out[out_idx + 1] = (uchar)(rgb.y); out[out_idx + 1] = (uchar)(rgb.y);
out[out_idx + 2] = (uchar)(rgb.x); out[out_idx + 2] = (uchar)(rgb.x);
} }

@ -34,8 +34,6 @@ int main() {
float rtol = 0.05; float rtol = 0.05;
// generate pattern and calculate EV // generate pattern and calculate EV
int cnt = 0; int cnt = 0;
for (int is_qcom2=0; is_qcom2<2; is_qcom2++) {
for (int g=0; g<GAIN_SPLITS; g++) {
for (int i_0=0; i_0<TONE_SPLITS; i_0++) { for (int i_0=0; i_0<TONE_SPLITS; i_0++) {
for (int i_1=0; i_1<TONE_SPLITS; i_1++) { for (int i_1=0; i_1<TONE_SPLITS; i_1++) {
for (int i_2=0; i_2<TONE_SPLITS; i_2++) { for (int i_2=0; i_2<TONE_SPLITS; i_2++) {
@ -50,7 +48,7 @@ int main() {
memset(&fb_y[h_0*W+h_1*W], l[2], h_2*W); memset(&fb_y[h_0*W+h_1*W], l[2], h_2*W);
memset(&fb_y[h_0*W+h_1*W+h_2*W], l[3], h_3*W); memset(&fb_y[h_0*W+h_1*W+h_2*W], l[3], h_3*W);
memset(&fb_y[h_0*W+h_1*W+h_2*W+h_3*W], l[4], h_4*W); memset(&fb_y[h_0*W+h_1*W+h_2*W+h_3*W], l[4], h_4*W);
float ev = set_exposure_target((const CameraBuf*) &cb, 0, W-1, 1, 0, H-1, 1, g*10, (bool)is_qcom2, (bool)is_qcom2); float ev = set_exposure_target((const CameraBuf*) &cb, 0, W-1, 1, 0, H-1, 1);
// printf("%d/%d/%d/%d/%d ev is %f\n", h_0, h_1, h_2, h_3, h_4, ev); // printf("%d/%d/%d/%d/%d ev is %f\n", h_0, h_1, h_2, h_3, h_4, ev);
// printf("%f\n", ev); // printf("%f\n", ev);
@ -61,14 +59,12 @@ int main() {
} }
// report // report
printf("%d/%d/%d/%d/%d/%d/%d: ev %f, gt %f, err %f\n", is_qcom2, g*10, h_0, h_1, h_2, h_3, h_4, ev, evgt, fabs(ev - evgt) / (evgt != 0 ? evgt : 0.00001f)); printf("%d/%d/%d/%d/%d: ev %f, gt %f, err %f\n", h_0, h_1, h_2, h_3, h_4, ev, evgt, fabs(ev - evgt) / (evgt != 0 ? evgt : 0.00001f));
cnt++; cnt++;
} }
} }
} }
} }
}
}
assert(passed); assert(passed);
delete[] fb_y; delete[] fb_y;

@ -4,9 +4,8 @@
#define H 160 #define H 160
#define TONE_SPLITS 3 #define TONE_SPLITS 3
#define GAIN_SPLITS 2
float gts[2*TONE_SPLITS*TONE_SPLITS*TONE_SPLITS*TONE_SPLITS*GAIN_SPLITS] = { float gts[TONE_SPLITS*TONE_SPLITS*TONE_SPLITS*TONE_SPLITS] = {
0.917969,0.917969,0.375000,0.917969,0.375000,0.375000,0.187500,0.187500,0.187500,0.917969, 0.917969,0.917969,0.375000,0.917969,0.375000,0.375000,0.187500,0.187500,0.187500,0.917969,
0.375000,0.375000,0.187500,0.187500,0.187500,0.187500,0.187500,0.187500,0.093750,0.093750, 0.375000,0.375000,0.187500,0.187500,0.187500,0.187500,0.187500,0.187500,0.093750,0.093750,
0.093750,0.093750,0.093750,0.093750,0.093750,0.093750,0.093750,0.917969,0.375000,0.375000, 0.093750,0.093750,0.093750,0.093750,0.093750,0.093750,0.093750,0.917969,0.375000,0.375000,
@ -15,29 +14,5 @@ float gts[2*TONE_SPLITS*TONE_SPLITS*TONE_SPLITS*TONE_SPLITS*GAIN_SPLITS] = {
0.093750,0.093750,0.093750,0.093750,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000, 0.093750,0.093750,0.093750,0.093750,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,
0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000, 0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,
0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000, 0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,
0.000000,0.917969,0.917969,0.375000,0.917969,0.375000,0.375000,0.187500,0.187500,0.187500, 0.000000
0.917969,0.375000,0.375000,0.187500,0.187500,0.187500,0.187500,0.187500,0.187500,0.093750,
0.093750,0.093750,0.093750,0.093750,0.093750,0.093750,0.093750,0.093750,0.917969,0.375000,
0.375000,0.187500,0.187500,0.187500,0.187500,0.187500,0.187500,0.093750,0.093750,0.093750,
0.093750,0.093750,0.093750,0.093750,0.093750,0.093750,0.093750,0.093750,0.093750,0.093750,
0.093750,0.093750,0.093750,0.093750,0.093750,0.000000,0.000000,0.000000,0.000000,0.000000,
0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,
0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,
0.000000,0.000000,4.527344,3.324219,0.457031,4.421875,3.265625,0.453125,4.324219,3.167969,
0.449219,4.421875,3.265625,0.453125,4.234375,3.113281,0.449219,3.980469,2.929688,0.441406,
4.324219,3.167969,0.449219,3.980469,2.929688,0.441406,3.558594,0.433594,0.433594,4.421875,
3.265625,0.453125,4.234375,3.113281,0.449219,3.980469,2.929688,0.441406,4.234375,3.113281,
0.449219,3.929688,2.902344,0.441406,3.484375,0.429688,0.429688,3.980469,2.929688,0.441406,
3.484375,0.429688,0.429688,2.871094,0.417969,0.417969,4.324219,3.167969,0.449219,3.980469,
2.929688,0.441406,3.558594,0.433594,0.433594,3.980469,2.929688,0.441406,3.484375,0.429688,
0.429688,2.871094,0.417969,0.417969,3.558594,0.433594,0.433594,2.871094,0.417969,0.417969,
0.308594,0.308594,0.308594,4.253906,3.140625,0.574219,4.156250,3.085938,0.566406,4.066406,
2.996094,0.562500,4.156250,3.085938,0.566406,3.984375,2.945312,0.554688,3.750000,2.777344,
0.542969,4.066406,2.996094,0.562500,3.750000,2.777344,0.542969,3.359375,0.519531,0.519531,
4.156250,3.085938,0.566406,3.984375,2.945312,0.554688,3.750000,2.777344,0.542969,3.984375,
2.945312,0.554688,3.699219,2.753906,0.539062,3.289062,0.515625,0.515625,3.750000,2.777344,
0.542969,3.289062,0.515625,0.515625,2.722656,0.480469,0.480469,4.066406,2.996094,0.562500,
3.750000,2.777344,0.542969,3.359375,0.519531,0.519531,3.750000,2.777344,0.542969,3.289062,
0.515625,0.515625,2.722656,0.480469,0.480469,3.359375,0.519531,0.519531,2.722656,0.480469,
0.480469,0.328125,0.328125,0.328125,
}; };

Loading…
Cancel
Save