camerad cleanup (#30573)

* misc cleanup

* rm those

* rm utils

* fix build

* rm pool

* little more

* goodbye imgproc
This commit is contained in:
Adeeb Shihadeh 2023-12-01 20:10:07 -08:00 committed by GitHub
parent 5dba9187e5
commit e34ee43eea
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
15 changed files with 59 additions and 370 deletions

View File

@ -29,8 +29,6 @@ camerad
^^^^^^^
.. autodoxygenindex::
:project: system_camerad_cameras
.. autodoxygenindex::
:project: system_camerad_imgproc
locationd
^^^^^^^^^

View File

@ -335,11 +335,6 @@ system/camerad/cameras/camera_common.h
system/camerad/cameras/camera_common.cc
system/camerad/cameras/sensor2_i2c.h
system/camerad/imgproc/conv.cl
system/camerad/imgproc/pool.cl
system/camerad/imgproc/utils.cc
system/camerad/imgproc/utils.h
selfdrive/manager/__init__.py
selfdrive/manager/build.py
selfdrive/manager/helpers.py

View File

@ -3,12 +3,7 @@ Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc')
libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', 'yuv', cereal, messaging, 'zmq', 'capnp', 'kj', visionipc, gpucommon, 'atomic']
camera_obj = env.Object(['cameras/camera_qcom2.cc', 'cameras/camera_common.cc', 'cameras/camera_util.cc'])
env.Program('camerad', [
'main.cc',
camera_obj,
], LIBS=libs)
env.Program('camerad', ['main.cc', camera_obj], LIBS=libs)
if GetOption("extras") and arch == "x86_64":
env.Program('test/ae_gray_test',
['test/ae_gray_test.cc', camera_obj],
LIBS=libs)
env.Program('test/ae_gray_test', ['test/ae_gray_test.cc', camera_obj], LIBS=libs)

View File

@ -11,7 +11,6 @@
#include "third_party/libyuv/include/libyuv.h"
#include <jpeglib.h>
#include "system/camerad/imgproc/utils.h"
#include "common/clutil.h"
#include "common/swaglog.h"
#include "common/util.h"
@ -93,12 +92,8 @@ void CameraBuf::init(cl_device_id device_id, cl_context context, CameraState *s,
debayer = new Debayer(device_id, context, this, s, nv12_width, nv12_uv_offset);
#ifdef __APPLE__
q = CL_CHECK_ERR(clCreateCommandQueue(context, device_id, 0, &err));
#else
const cl_queue_properties props[] = {0}; //CL_QUEUE_PRIORITY_KHR, CL_QUEUE_PRIORITY_HIGH_KHR, 0};
q = CL_CHECK_ERR(clCreateCommandQueueWithProperties(context, device_id, props, &err));
#endif
}
CameraBuf::~CameraBuf() {
@ -281,7 +276,6 @@ float set_exposure_target(const CameraBuf *b, int x_start, int x_end, int x_skip
}
}
// Find mean lumimance value
unsigned int lum_cur = 0;
for (lum_med = 255; lum_med >= 0; lum_med--) {

View File

@ -14,17 +14,9 @@
#include "common/swaglog.h"
#include "system/hardware/hw.h"
#define CAMERA_ID_IMX298 0
#define CAMERA_ID_IMX179 1
#define CAMERA_ID_S5K3P8SP 2
#define CAMERA_ID_OV8865 3
#define CAMERA_ID_IMX298_FLIPPED 4
#define CAMERA_ID_OV10640 5
#define CAMERA_ID_LGC920 6
#define CAMERA_ID_LGC615 7
#define CAMERA_ID_AR0231 8
#define CAMERA_ID_OX03C10 9
#define CAMERA_ID_MAX 10
#define CAMERA_ID_AR0231 0
#define CAMERA_ID_OX03C10 1
#define CAMERA_ID_MAX 2
const int YUV_BUFFER_COUNT = 20;
@ -55,7 +47,7 @@ typedef struct FrameMetadata {
uint32_t frame_id;
// Timestamps
uint64_t timestamp_sof; // only set on tici
uint64_t timestamp_sof;
uint64_t timestamp_eof;
// Exposure

View File

@ -665,51 +665,51 @@ void CameraState::camera_open(MultiCameraState *multi_cam_state_, int camera_num
if (!enabled) return;
struct cam_isp_in_port_info in_port_info = {
.res_type = (uint32_t[]){CAM_ISP_IFE_IN_RES_PHY_0, CAM_ISP_IFE_IN_RES_PHY_1, CAM_ISP_IFE_IN_RES_PHY_2}[camera_num],
.res_type = (uint32_t[]){CAM_ISP_IFE_IN_RES_PHY_0, CAM_ISP_IFE_IN_RES_PHY_1, CAM_ISP_IFE_IN_RES_PHY_2}[camera_num],
.lane_type = CAM_ISP_LANE_TYPE_DPHY,
.lane_num = 4,
.lane_cfg = 0x3210,
.lane_type = CAM_ISP_LANE_TYPE_DPHY,
.lane_num = 4,
.lane_cfg = 0x3210,
.vc = 0x0,
.dt = dt,
.vc = 0x0,
.dt = dt,
.format = CAM_FORMAT_MIPI_RAW_12,
.test_pattern = 0x2, // 0x3?
.usage_type = 0x0,
.left_start = 0,
.left_stop = ci.frame_width - 1,
.left_width = ci.frame_width,
.right_start = 0,
.right_stop = ci.frame_width - 1,
.right_width = ci.frame_width,
.line_start = 0,
.line_stop = ci.frame_height + ci.extra_height - 1,
.height = ci.frame_height + ci.extra_height,
.pixel_clk = 0x0,
.batch_size = 0x0,
.dsp_mode = CAM_ISP_DSP_MODE_NONE,
.hbi_cnt = 0x0,
.custom_csid = 0x0,
.num_out_res = 0x1,
.data[0] = (struct cam_isp_out_port_info){
.res_type = CAM_ISP_IFE_OUT_RES_RDI_0,
.format = CAM_FORMAT_MIPI_RAW_12,
.test_pattern = 0x2, // 0x3?
.usage_type = 0x0,
.left_start = 0,
.left_stop = ci.frame_width - 1,
.left_width = ci.frame_width,
.right_start = 0,
.right_stop = ci.frame_width - 1,
.right_width = ci.frame_width,
.line_start = 0,
.line_stop = ci.frame_height + ci.extra_height - 1,
.width = ci.frame_width,
.height = ci.frame_height + ci.extra_height,
.pixel_clk = 0x0,
.batch_size = 0x0,
.dsp_mode = CAM_ISP_DSP_MODE_NONE,
.hbi_cnt = 0x0,
.custom_csid = 0x0,
.num_out_res = 0x1,
.data[0] = (struct cam_isp_out_port_info){
.res_type = CAM_ISP_IFE_OUT_RES_RDI_0,
.format = CAM_FORMAT_MIPI_RAW_12,
.width = ci.frame_width,
.height = ci.frame_height + ci.extra_height,
.comp_grp_id = 0x0, .split_point = 0x0, .secure_mode = 0x0,
},
.comp_grp_id = 0x0, .split_point = 0x0, .secure_mode = 0x0,
},
};
struct cam_isp_resource isp_resource = {
.resource_id = CAM_ISP_RES_ID_PORT,
.handle_type = CAM_HANDLE_USER_POINTER,
.res_hdl = (uint64_t)&in_port_info,
.length = sizeof(in_port_info),
.resource_id = CAM_ISP_RES_ID_PORT,
.handle_type = CAM_HANDLE_USER_POINTER,
.res_hdl = (uint64_t)&in_port_info,
.length = sizeof(in_port_info),
};
auto isp_dev_handle_ = device_acquire(multi_cam_state->isp_fd, session_handle, &isp_resource);
@ -1098,8 +1098,8 @@ void CameraState::set_camera_exposure(float grey_frac) {
std::string gain_bytes, time_bytes;
if (env_ctrl_exp_from_params) {
gain_bytes = Params().get("CameraDebugExpGain");
time_bytes = Params().get("CameraDebugExpTime");
gain_bytes = params.get("CameraDebugExpGain");
time_bytes = params.get("CameraDebugExpTime");
}
if (gain_bytes.size() > 0 && time_bytes.size() > 0) {

View File

@ -107,6 +107,9 @@ private:
// Register parsing
std::map<uint16_t, std::pair<int, int>> ar0231_register_lut;
std::map<uint16_t, std::pair<int, int>> ar0231_build_register_lut(uint8_t *data);
// for debugging
Params params;
};
typedef struct MultiCameraState {

View File

@ -30,10 +30,10 @@ int do_cam_control(int fd, int op_code, void *handle, int size) {
std::optional<int32_t> device_acquire(int fd, int32_t session_handle, void *data, uint32_t num_resources) {
struct cam_acquire_dev_cmd cmd = {
.session_handle = session_handle,
.handle_type = CAM_HANDLE_USER_POINTER,
.num_resources = (uint32_t)(data ? num_resources : 0),
.resource_hdl = (uint64_t)data,
.session_handle = session_handle,
.handle_type = CAM_HANDLE_USER_POINTER,
.num_resources = (uint32_t)(data ? num_resources : 0),
.resource_hdl = (uint64_t)data,
};
int err = do_cam_control(fd, CAM_ACQUIRE_DEV, &cmd, sizeof(cmd));
return err == 0 ? std::make_optional(cmd.dev_handle) : std::nullopt;
@ -41,9 +41,9 @@ std::optional<int32_t> device_acquire(int fd, int32_t session_handle, void *data
int device_config(int fd, int32_t session_handle, int32_t dev_handle, uint64_t packet_handle) {
struct cam_config_dev_cmd cmd = {
.session_handle = session_handle,
.dev_handle = dev_handle,
.packet_handle = packet_handle,
.session_handle = session_handle,
.dev_handle = dev_handle,
.packet_handle = packet_handle,
};
return do_cam_control(fd, CAM_CONFIG_DEV, &cmd, sizeof(cmd));
}

View File

@ -1,6 +1,6 @@
#pragma once
#include <functional>
#include <functional>
#include <map>
#include <memory>
#include <mutex>

View File

@ -1,110 +0,0 @@
// const __constant float3 rgb_weights = (0.299, 0.587, 0.114); // opencv rgb2gray weights
// const __constant float3 bgr_weights = (0.114, 0.587, 0.299); // bgr2gray weights
// convert input rgb image to single channel then conv
__kernel void rgb2gray_conv2d(
const __global uchar * input,
__global short * output,
__constant short * filter,
__local uchar3 * cached
)
{
const int rowOffset = get_global_id(1) * IMAGE_W;
const int my = get_global_id(0) + rowOffset;
const int localRowLen = TWICE_HALF_FILTER_SIZE + get_local_size(0);
const int localRowOffset = ( get_local_id(1) + HALF_FILTER_SIZE ) * localRowLen;
const int myLocal = localRowOffset + get_local_id(0) + HALF_FILTER_SIZE;
// cache local pixels
cached[ myLocal ].x = input[ my * 3 ]; // r
cached[ myLocal ].y = input[ my * 3 + 1]; // g
cached[ myLocal ].z = input[ my * 3 + 2]; // b
// pad
if (
get_global_id(0) < HALF_FILTER_SIZE ||
get_global_id(0) > IMAGE_W - HALF_FILTER_SIZE - 1 ||
get_global_id(1) < HALF_FILTER_SIZE ||
get_global_id(1) > IMAGE_H - HALF_FILTER_SIZE - 1
)
{
barrier(CLK_LOCAL_MEM_FENCE);
return;
}
else
{
int localColOffset = -1;
int globalColOffset = -1;
// cache extra
if ( get_local_id(0) < HALF_FILTER_SIZE )
{
localColOffset = get_local_id(0);
globalColOffset = -HALF_FILTER_SIZE;
cached[ localRowOffset + get_local_id(0) ].x = input[ my * 3 - HALF_FILTER_SIZE * 3 ];
cached[ localRowOffset + get_local_id(0) ].y = input[ my * 3 - HALF_FILTER_SIZE * 3 + 1];
cached[ localRowOffset + get_local_id(0) ].z = input[ my * 3 - HALF_FILTER_SIZE * 3 + 2];
}
else if ( get_local_id(0) >= get_local_size(0) - HALF_FILTER_SIZE )
{
localColOffset = get_local_id(0) + TWICE_HALF_FILTER_SIZE;
globalColOffset = HALF_FILTER_SIZE;
cached[ myLocal + HALF_FILTER_SIZE ].x = input[ my * 3 + HALF_FILTER_SIZE * 3 ];
cached[ myLocal + HALF_FILTER_SIZE ].y = input[ my * 3 + HALF_FILTER_SIZE * 3 + 1];
cached[ myLocal + HALF_FILTER_SIZE ].z = input[ my * 3 + HALF_FILTER_SIZE * 3 + 2];
}
if ( get_local_id(1) < HALF_FILTER_SIZE )
{
cached[ get_local_id(1) * localRowLen + get_local_id(0) + HALF_FILTER_SIZE ].x = input[ my * 3 - HALF_FILTER_SIZE_IMAGE_W * 3 ];
cached[ get_local_id(1) * localRowLen + get_local_id(0) + HALF_FILTER_SIZE ].y = input[ my * 3 - HALF_FILTER_SIZE_IMAGE_W * 3 + 1];
cached[ get_local_id(1) * localRowLen + get_local_id(0) + HALF_FILTER_SIZE ].z = input[ my * 3 - HALF_FILTER_SIZE_IMAGE_W * 3 + 2];
if (localColOffset > 0)
{
cached[ get_local_id(1) * localRowLen + localColOffset ].x = input[ my * 3 - HALF_FILTER_SIZE_IMAGE_W * 3 + globalColOffset * 3];
cached[ get_local_id(1) * localRowLen + localColOffset ].y = input[ my * 3 - HALF_FILTER_SIZE_IMAGE_W * 3 + globalColOffset * 3 + 1];
cached[ get_local_id(1) * localRowLen + localColOffset ].z = input[ my * 3 - HALF_FILTER_SIZE_IMAGE_W * 3 + globalColOffset * 3 + 2];
}
}
else if ( get_local_id(1) >= get_local_size(1) -HALF_FILTER_SIZE )
{
int offset = ( get_local_id(1) + TWICE_HALF_FILTER_SIZE ) * localRowLen;
cached[ offset + get_local_id(0) + HALF_FILTER_SIZE ].x = input[ my * 3 + HALF_FILTER_SIZE_IMAGE_W * 3 ];
cached[ offset + get_local_id(0) + HALF_FILTER_SIZE ].y = input[ my * 3 + HALF_FILTER_SIZE_IMAGE_W * 3 + 1];
cached[ offset + get_local_id(0) + HALF_FILTER_SIZE ].z = input[ my * 3 + HALF_FILTER_SIZE_IMAGE_W * 3 + 2];
if (localColOffset > 0)
{
cached[ offset + localColOffset ].x = input[ my * 3 + HALF_FILTER_SIZE_IMAGE_W * 3 + globalColOffset * 3];
cached[ offset + localColOffset ].y = input[ my * 3 + HALF_FILTER_SIZE_IMAGE_W * 3 + globalColOffset * 3 + 1];
cached[ offset + localColOffset ].z = input[ my * 3 + HALF_FILTER_SIZE_IMAGE_W * 3 + globalColOffset * 3 + 2];
}
}
// sync
barrier(CLK_LOCAL_MEM_FENCE);
// perform convolution
int fIndex = 0;
short sum = 0;
for (int r = -HALF_FILTER_SIZE; r <= HALF_FILTER_SIZE; r++)
{
int curRow = r * localRowLen;
for (int c = -HALF_FILTER_SIZE; c <= HALF_FILTER_SIZE; c++, fIndex++)
{
if (!FLIP_RB){
// sum += dot(rgb_weights, cached[ myLocal + curRow + c ]) * filter[ fIndex ];
sum += (cached[ myLocal + curRow + c ].x / 3 + cached[ myLocal + curRow + c ].y / 2 + cached[ myLocal + curRow + c ].z / 9) * filter[ fIndex ];
} else {
// sum += dot(bgr_weights, cached[ myLocal + curRow + c ]) * filter[ fIndex ];
sum += (cached[ myLocal + curRow + c ].x / 9 + cached[ myLocal + curRow + c ].y / 2 + cached[ myLocal + curRow + c ].z / 3) * filter[ fIndex ];
}
}
}
output[my] = sum;
}
}

View File

@ -1,34 +0,0 @@
// calculate variance in each subregion
__kernel void var_pool(
const __global char * input,
__global ushort * output // should not be larger than 128*128 so uint16
)
{
const int xidx = get_global_id(0) + ROI_X_MIN;
const int yidx = get_global_id(1) + ROI_Y_MIN;
const int size = X_PITCH * Y_PITCH;
float fsum = 0;
char mean, max;
for (int i = 0; i < size; i++) {
int x_offset = i % X_PITCH;
int y_offset = i / X_PITCH;
fsum += input[xidx*X_PITCH + yidx*Y_PITCH*FULL_STRIDE_X + x_offset + y_offset*FULL_STRIDE_X];
max = input[xidx*X_PITCH + yidx*Y_PITCH*FULL_STRIDE_X + x_offset + y_offset*FULL_STRIDE_X]>max ? input[xidx*X_PITCH + yidx*Y_PITCH*FULL_STRIDE_X + x_offset + y_offset*FULL_STRIDE_X]:max;
}
mean = convert_char_rte(fsum / size);
float fvar = 0;
for (int i = 0; i < size; i++) {
int x_offset = i % X_PITCH;
int y_offset = i / X_PITCH;
fvar += (input[xidx*X_PITCH + yidx*Y_PITCH*FULL_STRIDE_X + x_offset + y_offset*FULL_STRIDE_X] - mean) * (input[xidx*X_PITCH + yidx*Y_PITCH*FULL_STRIDE_X + x_offset + y_offset*FULL_STRIDE_X] - mean);
}
fvar = fvar / size;
output[(xidx-ROI_X_MIN)+(yidx-ROI_Y_MIN)*(ROI_X_MAX-ROI_X_MIN+1)] = convert_ushort_rte(5 * fvar + convert_float_rte(max));
}

View File

@ -1,106 +0,0 @@
#include "system/camerad/imgproc/utils.h"
#include <algorithm>
#include <cassert>
#include <cstdio>
#include <cmath>
#include <cstring>
const int16_t lapl_conv_krnl[9] = {0, 1, 0,
1, -4, 1,
0, 1, 0};
// calculate score based on laplacians in one area
uint16_t get_lapmap_one(const int16_t *lap, int x_pitch, int y_pitch) {
const int size = x_pitch * y_pitch;
// avg and max of roi
int16_t max = 0;
int sum = 0;
for (int i = 0; i < size; ++i) {
const int16_t v = lap[i];
sum += v;
if (v > max) max = v;
}
const int16_t mean = sum / size;
// var of roi
int var = 0;
for (int i = 0; i < size; ++i) {
var += std::pow(lap[i] - mean, 2);
}
const float fvar = (float)var / size;
return std::min(5 * fvar + max, (float)65535);
}
bool is_blur(const uint16_t *lapmap, const size_t size) {
float bad_sum = 0;
for (int i = 0; i < size; i++) {
if (lapmap[i] < LM_THRESH) {
bad_sum += 1 / (float)size;
}
}
return (bad_sum > LM_PREC_THRESH);
}
static cl_program build_conv_program(cl_device_id device_id, cl_context context, int image_w, int image_h, int filter_size) {
char args[4096];
snprintf(args, sizeof(args),
"-cl-fast-relaxed-math -cl-denorms-are-zero "
"-DIMAGE_W=%d -DIMAGE_H=%d -DFLIP_RB=%d "
"-DFILTER_SIZE=%d -DHALF_FILTER_SIZE=%d -DTWICE_HALF_FILTER_SIZE=%d -DHALF_FILTER_SIZE_IMAGE_W=%d",
image_w, image_h, 1,
filter_size, filter_size/2, (filter_size/2)*2, (filter_size/2)*image_w);
return cl_program_from_file(context, device_id, "imgproc/conv.cl", args);
}
LapConv::LapConv(cl_device_id device_id, cl_context ctx, int rgb_width, int rgb_height, int rgb_stride, int filter_size)
: width(rgb_width / NUM_SEGMENTS_X), height(rgb_height / NUM_SEGMENTS_Y), rgb_stride(rgb_stride),
roi_buf(width * height * 3), result_buf(width * height) {
prg = build_conv_program(device_id, ctx, width, height, filter_size);
krnl = CL_CHECK_ERR(clCreateKernel(prg, "rgb2gray_conv2d", &err));
// TODO: Removed CL_MEM_SVM_FINE_GRAIN_BUFFER, confirm it doesn't matter
roi_cl = CL_CHECK_ERR(clCreateBuffer(ctx, CL_MEM_READ_WRITE, roi_buf.size() * sizeof(roi_buf[0]), NULL, &err));
result_cl = CL_CHECK_ERR(clCreateBuffer(ctx, CL_MEM_READ_WRITE, result_buf.size() * sizeof(result_buf[0]), NULL, &err));
filter_cl = CL_CHECK_ERR(clCreateBuffer(ctx, CL_MEM_READ_ONLY | CL_MEM_COPY_HOST_PTR,
9 * sizeof(int16_t), (void *)&lapl_conv_krnl, &err));
}
LapConv::~LapConv() {
CL_CHECK(clReleaseMemObject(roi_cl));
CL_CHECK(clReleaseMemObject(result_cl));
CL_CHECK(clReleaseMemObject(filter_cl));
CL_CHECK(clReleaseKernel(krnl));
CL_CHECK(clReleaseProgram(prg));
}
uint16_t LapConv::Update(cl_command_queue q, const uint8_t *rgb_buf, const int roi_id) {
// sharpness scores
const int x_offset = ROI_X_MIN + roi_id % (ROI_X_MAX - ROI_X_MIN + 1);
const int y_offset = ROI_Y_MIN + roi_id / (ROI_X_MAX - ROI_X_MIN + 1);
const uint8_t *rgb_offset = rgb_buf + y_offset * height * rgb_stride + x_offset * width * 3;
for (int i = 0; i < height; ++i) {
memcpy(&roi_buf[i * width * 3], &rgb_offset[i * rgb_stride], width * 3);
}
constexpr int local_mem_size = (CONV_LOCAL_WORKSIZE + 2 * (3 / 2)) * (CONV_LOCAL_WORKSIZE + 2 * (3 / 2)) * (3 * sizeof(uint8_t));
const size_t global_work_size[] = {(size_t)width, (size_t)height};
const size_t local_work_size[] = {CONV_LOCAL_WORKSIZE, CONV_LOCAL_WORKSIZE};
CL_CHECK(clEnqueueWriteBuffer(q, roi_cl, CL_TRUE, 0, roi_buf.size() * sizeof(roi_buf[0]), roi_buf.data(), 0, 0, 0));
CL_CHECK(clSetKernelArg(krnl, 0, sizeof(cl_mem), (void *)&roi_cl));
CL_CHECK(clSetKernelArg(krnl, 1, sizeof(cl_mem), (void *)&result_cl));
CL_CHECK(clSetKernelArg(krnl, 2, sizeof(cl_mem), (void *)&filter_cl));
CL_CHECK(clSetKernelArg(krnl, 3, local_mem_size, 0));
cl_event conv_event;
CL_CHECK(clEnqueueNDRangeKernel(q, krnl, 2, NULL, global_work_size, local_work_size, 0, 0, &conv_event));
CL_CHECK(clWaitForEvents(1, &conv_event));
CL_CHECK(clReleaseEvent(conv_event));
CL_CHECK(clEnqueueReadBuffer(q, result_cl, CL_TRUE, 0,
result_buf.size() * sizeof(result_buf[0]), result_buf.data(), 0, 0, 0));
return get_lapmap_one(result_buf.data(), width, height);
}

View File

@ -1,37 +0,0 @@
#pragma once
#include <cstddef>
#include <cstdint>
#include <vector>
#include "common/clutil.h"
#define NUM_SEGMENTS_X 8
#define NUM_SEGMENTS_Y 6
#define ROI_X_MIN 1
#define ROI_X_MAX 6
#define ROI_Y_MIN 2
#define ROI_Y_MAX 3
#define LM_THRESH 120
#define LM_PREC_THRESH 0.9 // 90 perc is blur
#define CONV_LOCAL_WORKSIZE 16
class LapConv {
public:
LapConv(cl_device_id device_id, cl_context ctx, int rgb_width, int rgb_height, int rgb_stride, int filter_size);
~LapConv();
uint16_t Update(cl_command_queue q, const uint8_t *rgb_buf, const int roi_id);
private:
cl_mem roi_cl, result_cl, filter_cl;
cl_program prg;
cl_kernel krnl;
const int width, height;
const int rgb_stride;
std::vector<uint8_t> roi_buf;
std::vector<int16_t> result_buf;
};
bool is_blur(const uint16_t *lapmap, const size_t size);

View File

@ -8,7 +8,7 @@
int main(int argc, char *argv[]) {
if (Hardware::PC()) {
printf("camerad is not meant to run on PC\n");
printf("exiting, camerad is not meant to run on PC\n");
return 0;
}

View File

@ -13,7 +13,6 @@ from openpilot.system.hardware import PC
from openpilot.selfdrive.controls.lib.alertmanager import set_offroad_alert
from openpilot.selfdrive.manager.process_config import managed_processes
LM_THRESH = 120 # defined in system/camerad/imgproc/utils.h
VISION_STREAMS = {
"roadCameraState": VisionStreamType.VISION_STREAM_ROAD,