Skip to content

Commit

Permalink
camerad: renames (commaai#30649)
Browse files Browse the repository at this point in the history
* sensorinfo

* drop the camera
  • Loading branch information
adeebshihadeh authored Dec 8, 2023
1 parent 2590cf8 commit e757d9b
Show file tree
Hide file tree
Showing 6 changed files with 17 additions and 17 deletions.
4 changes: 2 additions & 2 deletions system/camerad/cameras/camera_common.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ class Debayer {
public:
Debayer(cl_device_id device_id, cl_context context, const CameraBuf *b, const CameraState *s, int buf_width, int uv_offset) {
char args[4096];
const CameraInfo *ci = s->ci.get();
const SensorInfo *ci = s->ci.get();
snprintf(args, sizeof(args),
"-cl-fast-relaxed-math -cl-denorms-are-zero "
"-DFRAME_WIDTH=%d -DFRAME_HEIGHT=%d -DFRAME_STRIDE=%d -DFRAME_OFFSET=%d "
Expand Down Expand Up @@ -66,7 +66,7 @@ void CameraBuf::init(cl_device_id device_id, cl_context context, CameraState *s,
this->yuv_type = init_yuv_type;
frame_buf_count = frame_cnt;

const CameraInfo *ci = s->ci.get();
const SensorInfo *ci = s->ci.get();
// RAW frame
const int frame_size = (ci->frame_height + ci->extra_height) * ci->frame_stride;
camera_bufs = std::make_unique<VisionBuf[]>(frame_buf_count);
Expand Down
4 changes: 2 additions & 2 deletions system/camerad/cameras/camera_qcom2.cc
Original file line number Diff line number Diff line change
Expand Up @@ -430,9 +430,9 @@ void CameraState::enqueue_req_multi(int start, int n, bool dp) {

void CameraState::camera_set_parameters() {
if (camera_id == CAMERA_ID_AR0231) {
ci = std::make_unique<CameraAR0231>();
ci = std::make_unique<AR0231>();
} else if (camera_id == CAMERA_ID_OX03C10) {
ci = std::make_unique<CameraOx03c10>();
ci = std::make_unique<OX03C10>();
} else {
assert(false);
}
Expand Down
2 changes: 1 addition & 1 deletion system/camerad/cameras/camera_qcom2.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
class CameraState {
public:
MultiCameraState *multi_cam_state;
std::unique_ptr<const CameraInfo> ci;
std::unique_ptr<const SensorInfo> ci;
bool enabled;

std::mutex exp_lock;
Expand Down
4 changes: 2 additions & 2 deletions system/camerad/sensors/ar0231.cc
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ float ar0231_parse_temp_sensor(uint16_t calib1, uint16_t calib2, uint16_t data_r

} // namespace

CameraAR0231::CameraAR0231() {
AR0231::AR0231() {
frame_width = FRAME_WIDTH;
frame_height = FRAME_HEIGHT;
frame_stride = FRAME_STRIDE;
Expand Down Expand Up @@ -160,7 +160,7 @@ void ar0231_process_registers(MultiCameraState *s, CameraState *c, cereal::Frame
}


std::vector<struct i2c_random_wr_payload> ar0231_get_exp_registers(const CameraInfo *ci, int exposure_time, int new_exp_g, bool dc_gain_enabled) {
std::vector<struct i2c_random_wr_payload> ar0231_get_exp_registers(const SensorInfo *ci, int exposure_time, int new_exp_g, bool dc_gain_enabled) {
uint16_t analog_gain_reg = 0xFF00 | (new_exp_g << 4) | new_exp_g;
return {
{0x3366, analog_gain_reg},
Expand Down
4 changes: 2 additions & 2 deletions system/camerad/sensors/ox03c10.cc
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ const uint32_t VS_TIME_MAX_OX03C10 = 34; // vs < 35

} // namespace

CameraOx03c10::CameraOx03c10() {
OX03C10::OX03C10() {
frame_width = FRAME_WIDTH;
frame_height = FRAME_HEIGHT;
frame_stride = FRAME_STRIDE; // (0xa80*12//8)
Expand Down Expand Up @@ -68,7 +68,7 @@ CameraOx03c10::CameraOx03c10() {
target_grey_factor = TARGET_GREY_FACTOR_OX03C10;
}

std::vector<struct i2c_random_wr_payload> ox03c10_get_exp_registers(const CameraInfo *ci, int exposure_time, int new_exp_g, bool dc_gain_enabled) {
std::vector<struct i2c_random_wr_payload> ox03c10_get_exp_registers(const SensorInfo *ci, int exposure_time, int new_exp_g, bool dc_gain_enabled) {
// t_HCG&t_LCG + t_VS on LPD, t_SPD on SPD
uint32_t hcg_time = exposure_time;
uint32_t lcg_time = hcg_time;
Expand Down
16 changes: 8 additions & 8 deletions system/camerad/sensors/sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,9 @@ const size_t FRAME_WIDTH = 1928;
const size_t FRAME_HEIGHT = 1208;
const size_t FRAME_STRIDE = 2896; // for 12 bit output. 1928 * 12 / 8 + 4 (alignment)

class CameraInfo {
class SensorInfo {
public:
CameraInfo() = default;
SensorInfo() = default;

uint32_t frame_width, frame_height;
uint32_t frame_stride;
Expand Down Expand Up @@ -44,16 +44,16 @@ class CameraInfo {
float max_ev;
};

class CameraAR0231 : public CameraInfo {
class AR0231 : public SensorInfo {
public:
CameraAR0231();
AR0231();
};

class CameraOx03c10 : public CameraInfo {
class OX03C10 : public SensorInfo {
public:
CameraOx03c10();
OX03C10();
};

void ar0231_process_registers(MultiCameraState *s, CameraState *c, cereal::FrameData::Builder &framed);
std::vector<struct i2c_random_wr_payload> ox03c10_get_exp_registers(const CameraInfo *ci, int exposure_time, int new_exp_g, bool dc_gain_enabled);
std::vector<struct i2c_random_wr_payload> ar0231_get_exp_registers(const CameraInfo *ci, int exposure_time, int new_exp_g, bool dc_gain_enabled);
std::vector<struct i2c_random_wr_payload> ox03c10_get_exp_registers(const SensorInfo *ci, int exposure_time, int new_exp_g, bool dc_gain_enabled);
std::vector<struct i2c_random_wr_payload> ar0231_get_exp_registers(const SensorInfo *ci, int exposure_time, int new_exp_g, bool dc_gain_enabled);

0 comments on commit e757d9b

Please sign in to comment.