Paparazzi UAS  v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
mt9v117.c
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2016 Freek van Tienen <freek.v.tienen@gmail.com>
3  *
4  * This file is part of Paparazzi.
5  *
6  * Paparazzi is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2, or (at your option)
9  * any later version.
10  *
11  * Paparazzi is distributed in the hope that it will be useful,
12  * but WITHOUT ANY WARRANTY; without even the implied warranty of
13  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  * GNU General Public License for more details.
15  *
16  * You should have received a copy of the GNU General Public License
17  * along with paparazzi; see the file COPYING. If not, see
18  * <http://www.gnu.org/licenses/>.
19  *
20  */
21 
27 #include "std.h"
28 #include "mt9v117.h"
29 #include "mt9v117_regs.h"
31 
32 #include <stdio.h>
33 #include <unistd.h>
34 #include <fcntl.h>
35 #include <sys/ioctl.h>
36 #include <linux/i2c-dev.h>
37 #include <linux/videodev2.h>
38 #include <linux/v4l2-mediabus.h>
39 
40 #ifdef BOARD_DISCO
41 #include "boards/disco.h"
42 #else
43 #include "boards/bebop.h"
44 #endif
45 
46 
47 /* Camera structure */
49  .output_size = {
50  .w = 240,
51  .h = 240
52  },
53  .sensor_size = {
54  .w = 320,
55  .h = 240,
56  },
57  .crop = {
58  .x = 40,
59  .y = 0,
60  .w = 240,
61  .h = 240
62  },
63  .dev_name = "/dev/video0",
64  .subdev_name = "/dev/v4l-subdev0",
65  .format = V4L2_PIX_FMT_UYVY,
66  .subdev_format = V4L2_MBUS_FMT_UYVY8_2X8,
67  .buf_cnt = 5,
68  .filters = 0,
69  .cv_listener = NULL,
70  .fps = MT9V117_TARGET_FPS,
71  .camera_intrinsics = {
72  .focal_x = MT9V117_FOCAL_X,
73  .focal_y = MT9V117_FOCAL_Y,
74  .center_x = MT9V117_CENTER_X,
75  .center_y = MT9V117_CENTER_Y,
76  .Dhane_k = MT9V117_DHANE_K
77  }
78 };
79 
80 struct mt9v117_t mt9v117 = {
81  .i2c_periph = &i2c0
82 };
83 
84 /* Patch lines */
85 //I2C_BUF_LEN must be higher then size of these patch lines
86 #define MT9V117_PATCH_LINE_NUM 13
87 static uint8_t patch_line1[] = {
88  0xf0, 0x00, 0x72, 0xcf, 0xff, 0x00, 0x3e, 0xd0, 0x92, 0x00,
89  0x71, 0xcf, 0xff, 0xff, 0xf2, 0x18, 0xb1, 0x10, 0x92, 0x05,
90  0xb1, 0x11, 0x92, 0x04, 0xb1, 0x12, 0x70, 0xcf, 0xff, 0x00,
91  0x30, 0xc0, 0x90, 0x00, 0x7f, 0xe0, 0xb1, 0x13, 0x70, 0xcf,
92  0xff, 0xff, 0xe7, 0x1c, 0x88, 0x36, 0x09, 0x0f, 0x00, 0xb3
93 };
94 
95 static uint8_t patch_line2[] = {
96  0xf0, 0x30, 0x69, 0x13, 0xe1, 0x80, 0xd8, 0x08, 0x20, 0xca,
97  0x03, 0x22, 0x71, 0xcf, 0xff, 0xff, 0xe5, 0x68, 0x91, 0x35,
98  0x22, 0x0a, 0x1f, 0x80, 0xff, 0xff, 0xf2, 0x18, 0x29, 0x05,
99  0x00, 0x3e, 0x12, 0x22, 0x11, 0x01, 0x21, 0x04, 0x0f, 0x81,
100  0x00, 0x00, 0xff, 0xf0, 0x21, 0x8c, 0xf0, 0x10, 0x1a, 0x22
101 };
102 
103 static uint8_t patch_line3[] = {
104  0xf0, 0x60, 0x10, 0x44, 0x12, 0x20, 0x11, 0x02, 0xf7, 0x87,
105  0x22, 0x4f, 0x03, 0x83, 0x1a, 0x20, 0x10, 0xc4, 0xf0, 0x09,
106  0xba, 0xae, 0x7b, 0x50, 0x1a, 0x20, 0x10, 0x84, 0x21, 0x45,
107  0x01, 0xc1, 0x1a, 0x22, 0x10, 0x44, 0x70, 0xcf, 0xff, 0x00,
108  0x3e, 0xd0, 0xb0, 0x60, 0xb0, 0x25, 0x7e, 0xe0, 0x78, 0xe0
109 };
110 
111 static uint8_t patch_line4[] = {
112  0xf0, 0x90, 0x71, 0xcf, 0xff, 0xff, 0xf2, 0x18, 0x91, 0x12,
113  0x72, 0xcf, 0xff, 0xff, 0xe7, 0x1c, 0x8a, 0x57, 0x20, 0x04,
114  0x0f, 0x80, 0x00, 0x00, 0xff, 0xf0, 0xe2, 0x80, 0x20, 0xc5,
115  0x01, 0x61, 0x20, 0xc5, 0x03, 0x22, 0xb1, 0x12, 0x71, 0xcf,
116  0xff, 0x00, 0x3e, 0xd0, 0xb1, 0x04, 0x7e, 0xe0, 0x78, 0xe0
117 };
118 
119 static uint8_t patch_line5[] = {
120  0xf0, 0xc0, 0x70, 0xcf, 0xff, 0xff, 0xe7, 0x1c, 0x88, 0x57,
121  0x71, 0xcf, 0xff, 0xff, 0xf2, 0x18, 0x91, 0x13, 0xea, 0x84,
122  0xb8, 0xa9, 0x78, 0x10, 0xf0, 0x03, 0xb8, 0x89, 0xb8, 0x8c,
123  0xb1, 0x13, 0x71, 0xcf, 0xff, 0x00, 0x30, 0xc0, 0xb1, 0x00,
124  0x7e, 0xe0, 0xc0, 0xf1, 0x09, 0x1e, 0x03, 0xc0, 0xc1, 0xa1
125 };
126 
127 static uint8_t patch_line6[] = {
128  0xf0, 0xf0, 0x75, 0x08, 0x76, 0x28, 0x77, 0x48, 0xc2, 0x40,
129  0xd8, 0x20, 0x71, 0xcf, 0x00, 0x03, 0x20, 0x67, 0xda, 0x02,
130  0x08, 0xae, 0x03, 0xa0, 0x73, 0xc9, 0x0e, 0x25, 0x13, 0xc0,
131  0x0b, 0x5e, 0x01, 0x60, 0xd8, 0x06, 0xff, 0xbc, 0x0c, 0xce,
132  0x01, 0x00, 0xd8, 0x00, 0xb8, 0x9e, 0x0e, 0x5a, 0x03, 0x20
133 };
134 
135 static uint8_t patch_line7[] = {
136  0xf1, 0x20, 0xd9, 0x01, 0xd8, 0x00, 0xb8, 0x9e, 0x0e, 0xb6,
137  0x03, 0x20, 0xd9, 0x01, 0x8d, 0x14, 0x08, 0x17, 0x01, 0x91,
138  0x8d, 0x16, 0xe8, 0x07, 0x0b, 0x36, 0x01, 0x60, 0xd8, 0x07,
139  0x0b, 0x52, 0x01, 0x60, 0xd8, 0x11, 0x8d, 0x14, 0xe0, 0x87,
140  0xd8, 0x00, 0x20, 0xca, 0x02, 0x62, 0x00, 0xc9, 0x03, 0xe0
141 };
142 
143 static uint8_t patch_line8[] = {
144  0xf1, 0x50, 0xc0, 0xa1, 0x78, 0xe0, 0xc0, 0xf1, 0x08, 0xb2,
145  0x03, 0xc0, 0x76, 0xcf, 0xff, 0xff, 0xe5, 0x40, 0x75, 0xcf,
146  0xff, 0xff, 0xe5, 0x68, 0x95, 0x17, 0x96, 0x40, 0x77, 0xcf,
147  0xff, 0xff, 0xe5, 0x42, 0x95, 0x38, 0x0a, 0x0d, 0x00, 0x01,
148  0x97, 0x40, 0x0a, 0x11, 0x00, 0x40, 0x0b, 0x0a, 0x01, 0x00
149 };
150 
151 static uint8_t patch_line9[] = {
152  0xf1, 0x80, 0x95, 0x17, 0xb6, 0x00, 0x95, 0x18, 0xb7, 0x00,
153  0x76, 0xcf, 0xff, 0xff, 0xe5, 0x44, 0x96, 0x20, 0x95, 0x15,
154  0x08, 0x13, 0x00, 0x40, 0x0e, 0x1e, 0x01, 0x20, 0xd9, 0x00,
155  0x95, 0x15, 0xb6, 0x00, 0xff, 0xa1, 0x75, 0xcf, 0xff, 0xff,
156  0xe7, 0x1c, 0x77, 0xcf, 0xff, 0xff, 0xe5, 0x46, 0x97, 0x40
157 };
158 
159 static uint8_t patch_line10[] = {
160  0xf1, 0xb0, 0x8d, 0x16, 0x76, 0xcf, 0xff, 0xff, 0xe5, 0x48,
161  0x8d, 0x37, 0x08, 0x0d, 0x00, 0x81, 0x96, 0x40, 0x09, 0x15,
162  0x00, 0x80, 0x0f, 0xd6, 0x01, 0x00, 0x8d, 0x16, 0xb7, 0x00,
163  0x8d, 0x17, 0xb6, 0x00, 0xff, 0xb0, 0xff, 0xbc, 0x00, 0x41,
164  0x03, 0xc0, 0xc0, 0xf1, 0x0d, 0x9e, 0x01, 0x00, 0xe8, 0x04
165 };
166 
167 static uint8_t patch_line11[] = {
168  0xf1, 0xe0, 0xff, 0x88, 0xf0, 0x0a, 0x0d, 0x6a, 0x01, 0x00,
169  0x0d, 0x8e, 0x01, 0x00, 0xe8, 0x7e, 0xff, 0x85, 0x0d, 0x72,
170  0x01, 0x00, 0xff, 0x8c, 0xff, 0xa7, 0xff, 0xb2, 0xd8, 0x00,
171  0x73, 0xcf, 0xff, 0xff, 0xf2, 0x40, 0x23, 0x15, 0x00, 0x01,
172  0x81, 0x41, 0xe0, 0x02, 0x81, 0x20, 0x08, 0xf7, 0x81, 0x34
173 };
174 
175 static uint8_t patch_line12[] = {
176  0xf2, 0x10, 0xa1, 0x40, 0xd8, 0x00, 0xc0, 0xd1, 0x7e, 0xe0,
177  0x53, 0x51, 0x30, 0x34, 0x20, 0x6f, 0x6e, 0x5f, 0x73, 0x74,
178  0x61, 0x72, 0x74, 0x5f, 0x73, 0x74, 0x72, 0x65, 0x61, 0x6d,
179  0x69, 0x6e, 0x67, 0x20, 0x25, 0x64, 0x20, 0x25, 0x64, 0x0a,
180  0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
181 };
182 
183 static uint8_t patch_line13[] = {
184  0xf2, 0x40, 0xff, 0xff, 0xe8, 0x28, 0xff, 0xff, 0xf0, 0xe8,
185  0xff, 0xff, 0xe8, 0x08, 0xff, 0xff, 0xf1, 0x54
186 };
187 
188 /* Patch lines structure */
192 };
193 
195  {patch_line1, sizeof(patch_line1)},
196  {patch_line2, sizeof(patch_line2)},
197  {patch_line3, sizeof(patch_line3)},
198  {patch_line4, sizeof(patch_line4)},
199  {patch_line5, sizeof(patch_line5)},
200  {patch_line6, sizeof(patch_line6)},
201  {patch_line7, sizeof(patch_line7)},
202  {patch_line8, sizeof(patch_line8)},
203  {patch_line9, sizeof(patch_line9)},
204  {patch_line10, sizeof(patch_line10)},
205  {patch_line11, sizeof(patch_line11)},
206  {patch_line12, sizeof(patch_line12)},
207  {patch_line13, sizeof(patch_line13)}
208 };
209 
213 static void write_reg(struct mt9v117_t *mt, uint16_t addr, uint32_t val, uint16_t len)
214 {
215  mt->i2c_trans.buf[0] = addr >> 8;
216  mt->i2c_trans.buf[1] = addr & 0xFF;
217 
218  // Fix sigdness based on length
219  if (len == 1) {
220  mt->i2c_trans.buf[2] = val & 0xFF;
221  } else if (len == 2) {
222  mt->i2c_trans.buf[2] = (val >> 8) & 0xFF;
223  mt->i2c_trans.buf[3] = val & 0xFF;
224  } else if (len == 4) {
225  mt->i2c_trans.buf[2] = (val >> 24) & 0xFF;
226  mt->i2c_trans.buf[3] = (val >> 16) & 0xFF;
227  mt->i2c_trans.buf[4] = (val >> 8) & 0xFF;
228  mt->i2c_trans.buf[5] = val & 0xFF;
229  } else {
230  printf("[MT9V117] write_reg with incorrect length %d\r\n", len);
231  }
232 
233  // Transmit the buffer
235 }
236 
240 static uint32_t read_reg(struct mt9v117_t *mt, uint16_t addr, uint16_t len)
241 {
242  uint32_t ret = 0;
243  mt->i2c_trans.buf[0] = addr >> 8;
244  mt->i2c_trans.buf[1] = addr & 0xFF;
245 
246  // Transmit the buffer and receive back
248 
249  /* Fix sigdness */
250  for (uint8_t i = 0; i < len; i++) {
251  ret |= mt->i2c_trans.buf[len - i - 1] << (8 * i);
252  }
253  return ret;
254 }
255 
256 /* Write a byte to a var */
258 {
259  uint16_t addr = 0x8000 | (var << 10) | offset;
260  write_reg(mt, addr, val, len);
261 }
262 
263 /* Read a byte from a var */
265 {
266  uint16_t addr = 0x8000 | (var << 10) | offset;
267  return read_reg(mt, addr, len);
268 }
269 
270 static inline void mt9v117_write_patch(struct mt9v117_t *mt)
271 {
272  /* Errata item 2 */
273  write_reg(mt, 0x301a, 0x10d0, 2);
274  write_reg(mt, 0x31c0, 0x1404, 2);
275  write_reg(mt, 0x3ed8, 0x879c, 2);
276  write_reg(mt, 0x3042, 0x20e1, 2);
277  write_reg(mt, 0x30d4, 0x8020, 2);
278  write_reg(mt, 0x30c0, 0x0026, 2);
279  write_reg(mt, 0x301a, 0x10d4, 2);
280 
281  /* Errata item 6 */
282  write_var(mt, MT9V117_AE_TRACK_VAR, 0x0002, 0x00d3, 2);
283  write_var(mt, MT9V117_CAM_CTRL_VAR, 0x0078, 0x00a0, 2);
284  write_var(mt, MT9V117_CAM_CTRL_VAR, 0x0076, 0x0140, 2);
285 
286  /* Errata item 8 */
287  write_var(mt, MT9V117_LOW_LIGHT_VAR, 0x0004, 0x00fc, 2);
288  write_var(mt, MT9V117_LOW_LIGHT_VAR, 0x0038, 0x007f, 2);
289  write_var(mt, MT9V117_LOW_LIGHT_VAR, 0x003a, 0x007f, 2);
290  write_var(mt, MT9V117_LOW_LIGHT_VAR, 0x003c, 0x007f, 2);
291  write_var(mt, MT9V117_LOW_LIGHT_VAR, 0x0004, 0x00f4, 2);
292 
293  /* Patch 0403; Critical; Sensor optimization */
294  write_reg(mt, MT9V117_ACCESS_CTL_STAT, 0x0001, 2);
296 
297  /* Write patch */
298  for (uint8_t i = 0; i < MT9V117_PATCH_LINE_NUM; ++i) {
299  // Copy buffer
300  for (uint8_t j = 0; j < mt9v117_patch_lines[i].len; ++j) {
301  mt->i2c_trans.buf[j] = mt9v117_patch_lines[i].data[j];
302  }
303 
304  // Transmit the buffer
306  }
307 
313 
314  /* Wait for command OK */
315  for (uint8_t retries = 100; retries > 0; retries--) {
316  /* Wait 10ms */
317  usleep(10000);
318 
319  /* Check the command */
320  uint16_t cmd = read_reg(mt, MT9V117_COMMAND, 2);
321  if ((cmd & MT9V117_COMMAND_APPLY_PATCH) == 0) {
322  if ((cmd & MT9V117_COMMAND_OK) == 0) {
323  printf("[MT9V117] Applying patch failed (No OK)\r\n");
324  }
325  return;
326  }
327  }
328 
329  printf("[MT9V117] Applying patch failed after 10 retries\r\n");
330 }
331 
332 /* Configure the sensor */
333 static inline void mt9v117_config(struct mt9v117_t *mt)
334 {
345 
348 
351 
352  /* Set gain metric for 111.2 fps
353  * The final fps depends on the input clock
354  * (89.2fps on bebop) so a modification may be needed here */
357 
358  /* set crop window */
364 
365  /* Enable auto-stats mode */
374 }
375 
380 void mt9v117_init(struct mt9v117_t *mt)
381 {
382  /* bytes written to gpios/pwm */
383  int wc = 0;
384  /* Reset the device */
385  int gpio129 = open("/sys/class/gpio/gpio129/value", O_WRONLY | O_CREAT | O_TRUNC, 0666);
386  wc += write(gpio129, "0", 1);
387  wc += write(gpio129, "1", 1);
388  close(gpio129);
389 
390  if (wc != 2) {
391  printf("[MT9V117] Couldn't write to GPIO 129\n");
392  }
393 
394  /* Start PWM 9 (Which probably is the clock of the MT9V117) */
395  //#define BEBOP_CAMV_PWM_FREQ 43333333
396  int pwm9 = open("/sys/class/pwm/pwm_9/run", O_WRONLY | O_CREAT | O_TRUNC, 0666);
397  wc = 0;
398  wc += write(pwm9, "0", 1);
399  wc += write(pwm9, "1", 1);
400  close(pwm9);
401 
402  if (wc != 2) {
403  printf("[MT9V117] Couldn't write to PWM\n");
404  }
405 
406  //TODO: Make PWM and GPIO generic
407 
408  /* Wait 50ms */
409  usleep(50000);
410 
411  /* Setup i2c transaction */
413 
414  /* See if the device is there and correct */
415  uint16_t chip_id = read_reg(mt, MT9V117_CHIP_ID, 2);
416  if (chip_id != MT9V117_CHIP_ID_RESP) {
417  printf("[MT9V117] Didn't get correct response from CHIP_ID (expected: 0x%04X, got: 0x%04X)\r\n", MT9V117_CHIP_ID_RESP,
418  chip_id);
419  return;
420  }
421 
422  /* Reset the device with software */
425 
426  /* Wait 50ms */
427  usleep(50000);
428 
429  /* Apply MT9V117 software patch */
431 
432  /* Set basic settings */
435 
436  /* Set pixclk pad slew to 6 and data out pad slew to 1 */
437  write_reg(mt, MT9V117_PAD_SLEW, read_reg(mt, MT9V117_PAD_SLEW, 2) | 0x0600 | 0x0001, 2);
438 
439  /* Configure the MT9V117 sensor */
440  mt9v117_config(mt);
441 
442  /* Enable ITU656 */
446 
447  /* Set autoexposure luma */
449 
450  /* Apply the configuration */
453 
454  /* Wait for command OK */
455  for (uint8_t retries = 100; retries > 0; retries--) {
456  /* Wait 10ms */
457  usleep(10000);
458 
459  /* Check the command */
460  uint16_t cmd = read_reg(mt, MT9V117_COMMAND, 2);
461  if ((cmd & MT9V117_COMMAND_SET_STATE) == 0) {
462  if ((cmd & MT9V117_COMMAND_OK) == 0) {
463  printf("[MT9V117] Switching config failed (No OK)\r\n");
464  }
465 
466  // Successfully configured!
467  //printf("[MT9V117] Switching config OK\r\n");
468  return;
469  }
470  }
471 
472  printf("[MT9V117] Could not switch to new config\r\n");
473 }
static const float offset[]
volatile uint8_t buf[I2C_BUF_LEN]
Transaction buffer With I2C_BUF_LEN number of bytes.
Definition: i2c.h:122
enum I2CTransactionStatus status
Transaction status.
Definition: i2c.h:126
uint8_t slave_addr
Slave address.
Definition: i2c.h:104
bool i2c_blocking_transceive(struct i2c_periph *p, struct i2c_transaction *t, uint8_t s_addr, uint8_t len_w, uint16_t len_r)
Submit a write/read transaction and wait for it to complete.
Definition: i2c.c:403
bool i2c_blocking_transmit(struct i2c_periph *p, struct i2c_transaction *t, uint8_t s_addr, uint8_t len)
Submit a write only transaction and wait for it to complete.
Definition: i2c.c:359
@ I2CTransDone
transaction set to done by user level
Definition: i2c.h:59
uint16_t w
The width.
Definition: image.h:87
static uint8_t patch_line3[]
Definition: mt9v117.c:103
uint8_t * data
Definition: mt9v117.c:190
static uint8_t patch_line8[]
Definition: mt9v117.c:143
static uint8_t patch_line9[]
Definition: mt9v117.c:151
static const struct mt9v117_patch_t mt9v117_patch_lines[MT9V117_PATCH_LINE_NUM]
Definition: mt9v117.c:194
static uint8_t patch_line10[]
Definition: mt9v117.c:159
static uint8_t patch_line2[]
Definition: mt9v117.c:95
static uint8_t patch_line6[]
Definition: mt9v117.c:127
static uint8_t patch_line7[]
Definition: mt9v117.c:135
static uint8_t patch_line4[]
Definition: mt9v117.c:111
uint16_t len
Definition: mt9v117.c:191
static uint8_t patch_line13[]
Definition: mt9v117.c:183
static void write_reg(struct mt9v117_t *mt, uint16_t addr, uint32_t val, uint16_t len)
Write multiple bytes to a single register.
Definition: mt9v117.c:213
static uint32_t read_reg(struct mt9v117_t *mt, uint16_t addr, uint16_t len)
Read multiple bytes from a register.
Definition: mt9v117.c:240
static uint8_t patch_line12[]
Definition: mt9v117.c:175
void mt9v117_init(struct mt9v117_t *mt)
Initialisation of the Aptina MT9V117 CMOS sensor (1/6 inch VGA, bottom camera)
Definition: mt9v117.c:380
static void mt9v117_config(struct mt9v117_t *mt)
Definition: mt9v117.c:333
static uint8_t patch_line5[]
Definition: mt9v117.c:119
static uint8_t patch_line11[]
Definition: mt9v117.c:167
static void write_var(struct mt9v117_t *mt, uint16_t var, uint16_t offset, uint32_t val, uint16_t len)
Definition: mt9v117.c:257
static uint8_t patch_line1[]
Definition: mt9v117.c:87
struct video_config_t bottom_camera
Definition: mt9v117.c:48
static void mt9v117_write_patch(struct mt9v117_t *mt)
Definition: mt9v117.c:270
struct mt9v117_t mt9v117
Definition: mt9v117.c:80
#define MT9V117_PATCH_LINE_NUM
Definition: mt9v117.c:86
static uint32_t read_var(struct mt9v117_t *mt, uint16_t var, uint16_t offset, uint16_t len)
Definition: mt9v117.c:264
Initialization and configuration of the MT9V117 CMOS Chip.
#define MT9V117_CENTER_Y
Definition: mt9v117.h:50
#define MT9V117_TARGET_FPS
Definition: mt9v117.h:36
#define MT9V117_DHANE_K
Definition: mt9v117.h:53
#define MT9V117_FOCAL_X
Definition: mt9v117.h:41
#define MT9V117_CENTER_X
Definition: mt9v117.h:47
struct i2c_transaction i2c_trans
I2C transaction for comminication with CMOS chip.
Definition: mt9v117.h:61
#define MT9V117_TARGET_LUMA
Definition: mt9v117.h:56
struct i2c_periph * i2c_periph
I2C peripheral used to communicate over.
Definition: mt9v117.h:60
#define MT9V117_FOCAL_Y
Definition: mt9v117.h:44
#define MT9V117_LOW_LIGHT_VAR
Definition: mt9v117_regs.h:33
#define MT9V117_CAM_SENSOR_CONTROL_READ_MODE_OFFSET
Definition: mt9v117_regs.h:47
#define MT9V117_COMMAND_APPLY_PATCH
Definition: mt9v117_regs.h:17
#define MT9V117_CAM_SENSOR_CFG_X_ADDR_END_OFFSET
Definition: mt9v117_regs.h:38
#define MT9V117_PATCHLDR_PATCH_ID_OFFSET
Definition: mt9v117_regs.h:96
#define MT9V117_AE_TRACK_JUMP_DIVISOR
Definition: mt9v117_regs.h:21
#define MT9V117_CAM_OUTPUT_HEIGHT_OFFSET
Definition: mt9v117_regs.h:60
#define MT9V117_AE_TRACK_VAR
Definition: mt9v117_regs.h:30
#define MT9V117_PATCHLDR_LOADER_ADDRESS_OFFSET
Definition: mt9v117_regs.h:95
#define MT9V117_CAM_STAT_AE_INITIAL_WINDOW_XEND_OFFSET
Definition: mt9v117_regs.h:80
#define MT9V117_CAM_SENSOR_CFG_TARGET_FDZONE_60_OFFSET
Definition: mt9v117_regs.h:45
#define MT9V117_CAM_OUTPUT_FORMAT_OFFSET
Definition: mt9v117_regs.h:61
#define MT9V117_CAM_SENSOR_CFG_Y_ADDR_END_OFFSET
Definition: mt9v117_regs.h:37
#define MT9V117_CAM_STAT_AE_INITIAL_WINDOW_YEND_OFFSET
Definition: mt9v117_regs.h:81
#define MT9V117_LOGICAL_ADDRESS_ACCESS
Definition: mt9v117_regs.h:20
#define MT9V117_COMMAND_SET_STATE
Definition: mt9v117_regs.h:16
#define MT9V117_PATCHLDR_FIRMWARE_ID_OFFSET
Definition: mt9v117_regs.h:97
#define MT9V117_CAM_STAT_AE_INITIAL_WINDOW_XSTART_OFFSET
Definition: mt9v117_regs.h:78
#define MT9V117_CAM_LL_STOP_GAIN_METRIC_OFFSET
Definition: mt9v117_regs.h:83
#define MT9V117_RESET_SOC_I2C
Definition: mt9v117_regs.h:10
#define MT9V117_CAM_SENSOR_CFG_Y_ADDR_START_OFFSET
Definition: mt9v117_regs.h:35
#define MT9V117_PATCHLDR_VAR
Definition: mt9v117_regs.h:94
#define MT9V117_AE_LUMA
Definition: mt9v117_regs.h:23
#define MT9V117_CHIP_ID
Request the chip ID.
Definition: mt9v117_regs.h:7
#define MT9V117_CAM_AET_SKIP_FRAMES
Definition: mt9v117_regs.h:22
#define MT9V117_CAM_SENSOR_CFG_X_ADDR_START_OFFSET
Definition: mt9v117_regs.h:36
#define MT9V117_CAM_STAT_AE_INITIAL_WINDOW_YSTART_OFFSET
Definition: mt9v117_regs.h:79
#define MT9V117_AWB_VAR
Definition: mt9v117_regs.h:31
#define MT9V117_CAM_STAT_AWB_HG_WINDOW_YSTART_OFFSET
Definition: mt9v117_regs.h:75
#define MT9V117_CHIP_ID_RESP
Should be the response to CHIP_ID.
Definition: mt9v117_regs.h:8
#define MT9V117_ADDRESS
The i2c address of the chip.
Definition: mt9v117_regs.h:4
#define MT9V117_CAM_CROP_WINDOW_YOFFSET_OFFSET
Definition: mt9v117_regs.h:55
#define MT9V117_CAM_CROP_MODE_OFFSET
Definition: mt9v117_regs.h:58
#define MT9V117_CAM_SENSOR_CFG_FRAME_LENGTH_LINES_OFFSET
Definition: mt9v117_regs.h:39
#define MT9V117_PAD_SLEW
Definition: mt9v117_regs.h:11
#define MT9V117_AE_RULE_ALGO_AVERAGE
Definition: mt9v117_regs.h:28
#define MT9V117_CAM_SENSOR_CFG_MAX_FDZONE_60_OFFSET
Definition: mt9v117_regs.h:43
#define MT9V117_COMMAND_OK
Definition: mt9v117_regs.h:13
#define MT9V117_CAM_STAT_AWB_HG_WINDOW_XEND_OFFSET
Definition: mt9v117_regs.h:76
#define MT9V117_CAM_SENSOR_CONTROL_Y_SKIP_EN
Definition: mt9v117_regs.h:48
#define MT9V117_AE_RULE_VAR
Definition: mt9v117_regs.h:26
#define MT9V117_CAM_OUTPUT_FORMAT_BT656_ENABLE
Definition: mt9v117_regs.h:70
#define MT9V117_PHYSICAL_ADDRESS_ACCESS
Definition: mt9v117_regs.h:19
#define MT9V117_COMMAND
Definition: mt9v117_regs.h:12
#define MT9V117_CAM_STAT_AWB_HG_WINDOW_YEND_OFFSET
Definition: mt9v117_regs.h:77
#define MT9V117_CAM_LL_START_GAIN_METRIC_OFFSET
Definition: mt9v117_regs.h:82
#define MT9V117_AWB_PIXEL_THRESHOLD_COUNT_OFFSET
Definition: mt9v117_regs.h:32
#define MT9V117_SYSMGR_VAR
Definition: mt9v117_regs.h:84
#define MT9V117_CAM_CROP_WINDOW_WIDTH_OFFSET
Definition: mt9v117_regs.h:56
#define MT9V117_CAM_CROP_WINDOW_XOFFSET_OFFSET
Definition: mt9v117_regs.h:54
#define MT9V117_AE_RULE_ALGO_OFFSET
Definition: mt9v117_regs.h:27
#define MT9V117_RESET_MISC_CTRL
Definition: mt9v117_regs.h:9
#define MT9V117_CAM_CTRL_VAR
Definition: mt9v117_regs.h:34
#define MT9V117_ACCESS_CTL_STAT
Definition: mt9v117_regs.h:18
#define MT9V117_CAM_OUTPUT_WIDTH_OFFSET
Definition: mt9v117_regs.h:59
#define MT9V117_SYS_STATE_ENTER_CONFIG_CHANGE
Definition: mt9v117_regs.h:86
#define MT9V117_SYSMGR_NEXT_STATE_OFFSET
Definition: mt9v117_regs.h:85
#define MT9V117_CAM_STAT_AWB_HG_WINDOW_XSTART_OFFSET
Definition: mt9v117_regs.h:74
#define MT9V117_CAM_SENSOR_CFG_CPIPE_LAST_ROW_OFFSET
Definition: mt9v117_regs.h:40
#define MT9V117_CAM_CROP_WINDOW_HEIGHT_OFFSET
Definition: mt9v117_regs.h:57
uint16_t val[TCOUPLE_NB]
struct img_size_t output_size
Output image size.
Definition: video_device.h:56
V4L2 device settings.
Definition: video_device.h:55
unsigned short uint16_t
Typedef defining 16 bit unsigned short type.
Definition: vl53l1_types.h:88
unsigned int uint32_t
Typedef defining 32 bit unsigned int type.
Definition: vl53l1_types.h:78
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.
Definition: vl53l1_types.h:98