Skip to content

Commit

Permalink
camerad cleanup (#30573)
Browse files Browse the repository at this point in the history
* misc cleanup

* rm those

* rm utils

* fix build

* rm pool

* little more

* goodbye imgproc
  • Loading branch information
adeebshihadeh authored Dec 2, 2023
1 parent 5dba918 commit e34ee43
Show file tree
Hide file tree
Showing 15 changed files with 56 additions and 367 deletions.
2 changes: 0 additions & 2 deletions docs/c_docs.rst
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,6 @@ camerad
^^^^^^^
.. autodoxygenindex::
:project: system_camerad_cameras
.. autodoxygenindex::
:project: system_camerad_imgproc

locationd
^^^^^^^^^
Expand Down
5 changes: 0 additions & 5 deletions release/files_common
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
9 changes: 2 additions & 7 deletions system/camerad/SConscript
Original file line number Diff line number Diff line change
Expand Up @@ -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)
6 changes: 0 additions & 6 deletions system/camerad/cameras/camera_common.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down Expand Up @@ -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() {
Expand Down Expand Up @@ -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--) {
Expand Down
16 changes: 4 additions & 12 deletions system/camerad/cameras/camera_common.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down Expand Up @@ -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
Expand Down
76 changes: 38 additions & 38 deletions system/camerad/cameras/camera_qcom2.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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,
.format = CAM_FORMAT_MIPI_RAW_12,
.vc = 0x0,
.dt = dt,
.format = CAM_FORMAT_MIPI_RAW_12,

.test_pattern = 0x2, // 0x3?
.usage_type = 0x0,
.test_pattern = 0x2, // 0x3?
.usage_type = 0x0,

.left_start = 0,
.left_stop = ci.frame_width - 1,
.left_width = ci.frame_width,
.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,
.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,
.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,
.width = ci.frame_width,
.height = ci.frame_height + ci.extra_height,
.comp_grp_id = 0x0, .split_point = 0x0, .secure_mode = 0x0,
},
.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,
},
};
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);
Expand Down Expand Up @@ -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) {
Expand Down
3 changes: 3 additions & 0 deletions system/camerad/cameras/camera_qcom2.h
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,9 @@ class CameraState {
// 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 {
Expand Down
14 changes: 7 additions & 7 deletions system/camerad/cameras/camera_util.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,20 +30,20 @@ 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;
}

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));
}
Expand Down
2 changes: 1 addition & 1 deletion system/camerad/cameras/camera_util.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#pragma once

#include <functional>
#include <functional>
#include <map>
#include <memory>
#include <mutex>
Expand Down
110 changes: 0 additions & 110 deletions system/camerad/imgproc/conv.cl

This file was deleted.

34 changes: 0 additions & 34 deletions system/camerad/imgproc/pool.cl

This file was deleted.

Loading

0 comments on commit e34ee43

Please sign in to comment.