17 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP 26 #define MT9V117_CHIP_ID 0x2282 27 #define COMMAND_REGISTER 0x0040 28 #define HOST_COMMAND_OK (1 << 15) 29 #define HOST_COMMAND_2 (1 << 2) 30 #define HOST_COMMAND_1 (1 << 1) 31 #define HOST_COMMAND_0 (1 << 0) 32 #define PAD_SLEW 0x0030 33 #define RESET_AND_MISC_CONTROL 0x001a 34 #define RESET_SOC_I2C (1 << 0) 35 #define ACCESS_CTL_STAT 0x0982 36 #define PHYSICAL_ADDRESS_ACCESS 0x098a 37 #define LOGICAL_ADDRESS_ACCESS 0x098e 38 #define AE_TRACK_JUMP_DIVISOR 0xa812 39 #define CAM_AET_SKIP_FRAMES 0xc868 42 #define AE_RULE_ALGO_OFFSET 4 43 #define AE_RULE_ALGO_AVERAGE 0 44 #define AE_RULE_ALGO_WEIGHTED 1 45 #define AE_TRACK_VAR 10 47 #define AWB_PIXEL_THRESHOLD_COUNT_OFFSET 64 48 #define LOW_LIGHT_VAR 15 49 #define CAM_CTRL_VAR 18 50 #define CAM_SENSOR_CFG_Y_ADDR_START_OFFSET 0 51 #define CAM_SENSOR_CFG_X_ADDR_START_OFFSET 2 52 #define CAM_SENSOR_CFG_Y_ADDR_END_OFFSET 4 53 #define CAM_SENSOR_CFG_X_ADDR_END_OFFSET 6 54 #define CAM_SENSOR_CFG_FRAME_LENGTH_LINES_OFFSET 14 55 #define CAM_SENSOR_CFG_CPIPE_LAST_ROW_OFFSET 20 56 #define CAM_SENSOR_CFG_FDPERIOD_60HZ 22 57 #define CAM_SENSOR_CFG_FDPERIOD_50HZ 24 58 #define CAM_SENSOR_CFG_MAX_FDZONE_60_OFFSET 26 59 #define CAM_SENSOR_CFG_MAX_FDZONE_50_OFFSET 28 60 #define CAM_SENSOR_CFG_TARGET_FDZONE_60_OFFSET 30 61 #define CAM_SENSOR_CFG_TARGET_FDZONE_50_OFFSET 32 62 #define CAM_SENSOR_CONTROL_READ_MODE_OFFSET 40 63 #define CAM_SENSOR_CONTROL_Y_SKIP_EN (1 << 2) 64 #define CAM_SENSOR_CONTROL_VERT_FLIP_EN (1 << 1) 65 #define CAM_SENSOR_CONTROL_HORZ_MIRROR_EN (1 << 0) 66 #define CAM_FLICKER_PERIOD_OFFSET 62 67 #define CAM_FLICKER_PERIOD_60HZ 0 68 #define CAM_FLICKER_PERIOD_50HZ 1 69 #define CAM_CROP_WINDOW_XOFFSET_OFFSET 72 70 #define CAM_CROP_WINDOW_YOFFSET_OFFSET 74 71 #define CAM_CROP_WINDOW_WIDTH_OFFSET 76 72 #define CAM_CROP_WINDOW_HEIGHT_OFFSET 78 73 #define CAM_CROP_MODE_OFFSET 80 74 #define CAM_OUTPUT_WIDTH_OFFSET 84 75 #define CAM_OUTPUT_HEIGHT_OFFSET 86 76 #define CAM_OUTPUT_FORMAT_OFFSET 88 77 #define CAM_OUTPUT_FORMAT_RGB_565 (0 << 12) 78 #define CAM_OUTPUT_FORMAT_RGB_555 (1 << 12) 79 #define CAM_OUTPUT_FORMAT_RGB_444X (2 << 12) 80 #define CAM_OUTPUT_FORMAT_RGB_X444 (3 << 12) 81 #define CAM_OUTPUT_FORMAT_BAYER_10 (0 << 10) 82 #define CAM_OUTPUT_FORMAT_YUV (0 << 8) 83 #define CAM_OUTPUT_FORMAT_RGB (1 << 8) 84 #define CAM_OUTPUT_FORMAT_BAYER (2 << 8) 85 #define CAM_OUTPUT_FORMAT_BT656_ENABLE (1 << 3) 86 #define CAM_OUTPUT_FORMAT_MONO_ENABLE (1 << 2) 87 #define CAM_OUTPUT_FORMAT_SWAP_BYTES (1 << 1) 88 #define CAM_OUTPUT_FORMAT_SWAP_RED_BLUE (1 << 0) 89 #define CAM_STAT_AWB_HG_WINDOW_XSTART_OFFSET 236 90 #define CAM_STAT_AWB_HG_WINDOW_YSTART_OFFSET 238 91 #define CAM_STAT_AWB_HG_WINDOW_XEND_OFFSET 240 92 #define CAM_STAT_AWB_HG_WINDOW_YEND_OFFSET 242 93 #define CAM_STAT_AE_INITIAL_WINDOW_XSTART_OFFSET 244 94 #define CAM_STAT_AE_INITIAL_WINDOW_YSTART_OFFSET 246 95 #define CAM_STAT_AE_INITIAL_WINDOW_XEND_OFFSET 248 96 #define CAM_STAT_AE_INITIAL_WINDOW_YEND_OFFSET 250 97 #define CAM_LL_START_GAIN_METRIC_OFFSET 278 98 #define CAM_LL_STOP_GAIN_METRIC_OFFSET 280 100 #define SYSMGR_NEXT_STATE_OFFSET 0 101 #define PATCHLDR_VAR 24 102 #define PATCHLDR_LOADER_ADDRESS_OFFSET 0 103 #define PATCHLDR_PATCH_ID_OFFSET 2 104 #define PATCHLDR_FIRMWARE_ID_OFFSET 4 108 using namespace Linux;
113 uint16_t nrst_gpio, uint32_t clock_freq)
115 , _dev(
std::move(dev))
116 , _nrst_gpio(nrst_gpio)
117 , _clock_freq(clock_freq)
120 AP_HAL::panic(
"Could not find I2C bus for CameraSensor_Mt9v117");
140 buf[0] = (uint8_t) (reg >> 8);
141 buf[1] = (uint8_t) (reg & 0xFF);
154 buf[0] = (uint8_t) (reg >> 8);
155 buf[1] = (uint8_t) (reg & 0xFF);
166 buf[0] = (uint8_t) (reg >> 8);
167 buf[1] = (uint8_t) (reg & 0xFF);
174 return (buf[0] << 8 | buf[1]);
180 buf[0] = (uint8_t) (reg >> 8);
181 buf[1] = (uint8_t) (reg & 0xFF);
182 buf[2] = (uint8_t) (val >> 8);
183 buf[3] = (uint8_t) (val & 0xFF);
193 buf[0] = (uint8_t) (reg >> 8);
194 buf[1] = (uint8_t) (reg & 0xFF);
195 buf[2] = (uint8_t) (val >> 24);
196 buf[3] = (uint8_t) ((val >> 16) & 0xFF);
197 buf[4] = (uint8_t) ((val >> 8) & 0xFF);
198 buf[5] = (uint8_t) (val & 0xFF);
208 return (0x8000 | (var << 10) | offset);
213 uint16_t reg =
_var2reg(var, offset);
221 uint16_t reg =
_var2reg(var, offset);
227 uint16_t reg =
_var2reg(var, offset);
235 uint16_t reg =
_var2reg(var, offset);
243 uint16_t reg =
_var2reg(var, offset);
266 "timeout waiting or command to complete\n");
403 gpio_source->
write(1);
404 uint32_t
delay = 3.5f + (35.0f - 3.5f) *
406 (54000000.0
f - 6000000.0
f);
CameraSensor_Mt9v117(const char *device_path, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, enum mt9v117_res res, uint16_t nrst_gpio, uint32_t clock_freq)
#define AE_RULE_ALGO_OFFSET
#define LOGICAL_ADDRESS_ACCESS
#define CAM_STAT_AWB_HG_WINDOW_YEND_OFFSET
AP_HAL::UARTDriver * console
void _write_var16(uint16_t var, uint16_t offset, uint16_t value)
#define CAM_CROP_WINDOW_WIDTH_OFFSET
#define CAM_SENSOR_CFG_TARGET_FDZONE_60_OFFSET
#define PATCHLDR_PATCH_ID_OFFSET
#define PHYSICAL_ADDRESS_ACCESS
void _write_var32(uint16_t var, uint16_t offset, uint32_t value)
#define CAM_STAT_AE_INITIAL_WINDOW_YEND_OFFSET
void _set_basic_settings()
uint8_t _read_reg8(uint16_t reg)
uint16_t _var2reg(uint16_t var, uint16_t offset)
#define PATCHLDR_LOADER_ADDRESS_OFFSET
#define CAM_SENSOR_CFG_X_ADDR_START_OFFSET
virtual void mode(uint8_t output)=0
#define CAM_SENSOR_CFG_X_ADDR_END_OFFSET
#define CAM_LL_START_GAIN_METRIC_OFFSET
#define CAM_CROP_WINDOW_HEIGHT_OFFSET
#define CAM_OUTPUT_HEIGHT_OFFSET
virtual void delay(uint16_t ms)=0
#define CAM_STAT_AE_INITIAL_WINDOW_YSTART_OFFSET
void _write_reg16(uint16_t reg, uint16_t val)
void _write_reg8(uint16_t reg, uint8_t val)
virtual void printf(const char *,...) FMT_PRINTF(2
#define CAM_OUTPUT_FORMAT_OFFSET
static AP_HAL::OwnPtr< AP_HAL::Device > dev
void _write_reg32(uint16_t reg, uint32_t val)
#define CAM_SENSOR_CFG_FRAME_LENGTH_LINES_OFFSET
#define CAM_OUTPUT_WIDTH_OFFSET
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override=0
#define AWB_PIXEL_THRESHOLD_COUNT_OFFSET
virtual AP_HAL::DigitalSource * channel(uint16_t n)=0
#define CAM_STAT_AE_INITIAL_WINDOW_XEND_OFFSET
#define CAM_STAT_AWB_HG_WINDOW_XEND_OFFSET
uint16_t _read_var16(uint16_t var, uint16_t offset)
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
#define AE_RULE_ALGO_AVERAGE
#define PATCHLDR_FIRMWARE_ID_OFFSET
#define CAM_SENSOR_CFG_Y_ADDR_START_OFFSET
#define CAM_SENSOR_CFG_MAX_FDZONE_60_OFFSET
void _configure_sensor_qvga()
#define CAM_SENSOR_CFG_CPIPE_LAST_ROW_OFFSET
#define MT9V117_PATCH_LINE_NUM
#define CAM_LL_STOP_GAIN_METRIC_OFFSET
#define CAM_CROP_WINDOW_XOFFSET_OFFSET
static const struct mt9v117_patch _patch_lines[MT9V117_PATCH_LINE_NUM]
#define CAM_SENSOR_CONTROL_Y_SKIP_EN
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void panic(const char *errormsg,...) FMT_PRINTF(1
#define AE_TRACK_JUMP_DIVISOR
#define CAM_STAT_AE_INITIAL_WINDOW_XSTART_OFFSET
#define CAM_SENSOR_CONTROL_READ_MODE_OFFSET
void _write_var8(uint16_t var, uint16_t offset, uint8_t value)
#define SYSMGR_NEXT_STATE_OFFSET
uint16_t _read_reg16(uint16_t reg)
#define CAM_CROP_WINDOW_YOFFSET_OFFSET
AP_HAL::Scheduler * scheduler
#define CAM_CROP_MODE_OFFSET
#define CAM_OUTPUT_FORMAT_BT656_ENABLE
#define RESET_AND_MISC_CONTROL
virtual void write(uint8_t value)=0
uint8_t _read_var8(uint16_t var, uint16_t offset)
#define CAM_AET_SKIP_FRAMES
#define CAM_SENSOR_CFG_Y_ADDR_END_OFFSET