├── LICENSE.md ├── README.md ├── arduvision_01 ├── arduino │ └── ov_fifo_test │ │ ├── IO_config.h │ │ ├── LICENSE.md │ │ ├── delay.h │ │ ├── fifo.cpp │ │ ├── fifo.h │ │ ├── ov7670_regs.h │ │ ├── ov772x_regs.h │ │ ├── ov_fifo_test.ino │ │ ├── sensor.cpp │ │ └── sensor.h ├── docs │ └── arduino_ov_fifo_connections.png └── processing │ └── receive_stream │ ├── LICENSE.md │ ├── globalDefinitions.java │ ├── receive_stream.pde │ └── simpleKalman.java └── arduvision_02_mega ├── arduino └── ov_fifo_test_mega │ ├── IO_config.h │ ├── LICENSE.md │ ├── delay.h │ ├── fifo.cpp │ ├── fifo.h │ ├── ov7670_regs.h │ ├── ov772x_regs.h │ ├── ov_fifo_test_mega.ino │ ├── sensor.cpp │ └── sensor.h ├── docs └── arduvision_ov7670_fino_mega.png └── processing └── receive_stream_mega ├── LICENSE.md ├── globalDefinitions.java ├── receive_stream_mega.pde └── simpleKalman.java /README.md: -------------------------------------------------------------------------------- 1 | arduvision 2 | ========== 3 | 4 | embedded computer vision with arduino 5 | http://therandomlab.blogspot.com.es/search/label/ov7670 6 | -------------------------------------------------------------------------------- /arduvision_01/arduino/ov_fifo_test/IO_config.h: -------------------------------------------------------------------------------- 1 | 2 | /******************************************************************* 3 | * 4 | * by David Sanz Kirbis 5 | * 6 | * Defines ports and pins used to connect an omnivision sensor+al422 7 | * fifo camera module to an ATmega 328p Pro Mini Arduino clone board. 8 | * The module tested with this setup has a 12MHz clock connected to 9 | * the sensor XCLK and the following header / pinout: 10 | * 11 | * GND --- 1 2 --- VCC3.3 12 | * OV_SCL --- 3 4 --- FIFO_WRST 13 | * OV_SDA --- 5 6 --- FIFO_RRST 14 | * FIFO_D0 --- 7 8 --- FIFO_OE 15 | * FIFO_D2 --- 9 10 --- FIFO_D1 16 | * FIFO_D4 --- 11 12 --- FIFO_D3 17 | * FIFO_D6 --- 13 14 --- FIFO_D5 18 | * FIFO_RCLK --- 15 16 --- FIFO_D7 19 | * FIFO_WEN --- 17 18 --- OV_VSYNC 20 | * 21 | * 22 | * The definitions and implementation design is based on: 23 | * arndtjenssen's ov7670_ports.h (Aug 18, 2013) 24 | * see: https://github.com/arndtjenssen/ov7670 25 | * 26 | * 2014 Aug 19 - Modified original file to be used with an 27 | * Atmega 328p 28 | * Aug 21 - Changed pin mapping to put all data pins in 29 | * the same port, to save 1/3rd of the time employed 30 | * to read data from the fifo IC (i.e., to read each 31 | * whole byte in just one instruction). 32 | * The LS bits of the pixel data coming from the modules 33 | * are discarded in order to be able to communicate to 34 | * the 328p through the hardware UART TX and RX pins 35 | * and allow uploding Arduino sketches. 36 | * Also, interrupt pin INT0 is kept available. 37 | * The resulting image quality shows the expected 38 | * banding due to the reduction of depth but it is 39 | * fair enough for detection purposes. 40 | * 41 | * 42 | * Wire the module as follows: 43 | * 44 | * 45 | * OV+FIFO ------ ATMEGA 328P (3.3V/8MHz) 46 | * 47 | * GND ------ GND 48 | * 3.3v ------ VCC 49 | * FIFO_OE ------ GND 50 | * FIFO_WEN ------ PB0/D8 51 | * FIFO_RCLK ------ PB1/D9 /PWM 52 | * ------ PB2/D10/PWM 53 | * ------ PB3/D11/PWM 54 | * FIFO_WRST ------ PB4/D12 55 | * FIFO_RRST ------ PB5/D13 56 | * PB6 - crystal 57 | * PB7 - crystal 58 | * 59 | * ------ PC0/A0 60 | * ------ PC1/A1 61 | * ------ PC2/A2 62 | * ------ PC3/A3 63 | * OV_SDA ------ PC4/A4/SDA 64 | * OV_SCL ------ PC5/A5/SCL 65 | * PC6/A6 - TQFP readonly 66 | * PC7/A7 - TQFP readonly 67 | * 68 | * PD0/D0 - TX 69 | * PD1/D1 - RX 70 | * OV_VSYNC ------ PD2/D2/INT0 71 | * FIFO_D3 ------ PD3/D3/INT1/PWM 72 | * FIFO_D4 ------ PD4/D4 73 | * FIFO_D5 ------ PD5/D5/PWM 74 | * FIFO_D6 ------ PD6/D6/PWM 75 | * FIFO_D7 ------ PD7/D7 76 | * 77 | * 78 | * 79 | ********************************************/ 80 | 81 | #ifndef IO_CONFIG_H_ 82 | #define IO_CONFIG_H_ 83 | 84 | #include 85 | 86 | 87 | // data pins -------------------- 88 | 89 | #define DATA_DDR DDRD 90 | #define DATA_PORT PORTD 91 | #define DATA_PINS PIND 92 | 93 | // control pins -------------------- 94 | #define VSYNC_INT 0 95 | 96 | #ifdef VSYNC_INT 97 | #define OV_VSYNC _BV(PIND2) 98 | #else 99 | #define OV_VSYNC _BV(PINB0) 100 | #endif 101 | 102 | #define FIFO_WREN _BV(PINB0) // Write Enable (active low) 103 | #define FIFO_RCLK _BV(PINB1) // Read clock 104 | #define FIFO_WRST _BV(PINB4) // Write Reset (active low) 105 | #define FIFO_RRST _BV(PINB5) // Read Reset (active low) 106 | 107 | #define WREN_DDR DDRB 108 | #define WREN_PORT PORTB 109 | 110 | #define RCLK_DDR DDRB 111 | #define RCLK_PORT PORTB 112 | 113 | #define WRST_DDR DDRB 114 | #define WRST_PORT PORTB 115 | 116 | #define RRST_DDR DDRB 117 | #define RRST_PORT PORTB 118 | 119 | #ifdef VSYNC_INT 120 | #define VSYNC_PIN PIND 121 | #define VSYNC_DDR DDRD 122 | #define VSYNC_PORT PORTD 123 | #else 124 | #define VSYNC_PIN PINB 125 | #define VSYNC_DDR DDRB 126 | #define VSYNC_PORT PORTB 127 | #endif 128 | 129 | #define GET_VSYNC (VSYNC_PIN & OV_VSYNC) 130 | 131 | #define DISABLE_RRST RRST_PORT|=FIFO_RRST 132 | #define ENABLE_RRST RRST_PORT&=~FIFO_RRST 133 | 134 | #define DISABLE_WRST WRST_PORT|=FIFO_WRST 135 | #define ENABLE_WRST WRST_PORT&=~FIFO_WRST 136 | 137 | #define SET_RCLK_H RCLK_PORT|=FIFO_RCLK 138 | #define SET_RCLK_L RCLK_PORT&=~FIFO_RCLK 139 | 140 | #define ENABLE_WREN WREN_PORT |= FIFO_WREN 141 | #define DISABLE_WREN WREN_PORT &= ~FIFO_WREN 142 | 143 | 144 | // ************************************* 145 | void static inline setup_IO_ports() { 146 | 147 | // reset registers and register directions 148 | DDRB = DDRD = PORTB = PORTD = 0; 149 | // set fifo data pins as inputs 150 | DATA_DDR = 0; // set pins as INPUTS 151 | 152 | WREN_DDR |= FIFO_WREN; // set pin as OUTPUT 153 | RCLK_DDR |= FIFO_RCLK; // set pin as OUTPUT 154 | RRST_DDR |= FIFO_RRST; // set pin as OUTPUT 155 | WRST_DDR |= FIFO_WRST; // set pin as OUTPUT 156 | 157 | VSYNC_DDR &= ~(OV_VSYNC); // set pin as INPUT 158 | #ifdef VSYNC_INT 159 | VSYNC_PORT |= OV_VSYNC; // enable pullup (for interruption handler) 160 | #endif 161 | } 162 | 163 | 164 | #endif /* IO_CONFIG_H_ */ 165 | -------------------------------------------------------------------------------- /arduvision_01/arduino/ov_fifo_test/delay.h: -------------------------------------------------------------------------------- 1 | /* 2 | * delay.h 3 | * 4 | * Provides accurate delays for a given number of nanoseconds 5 | * This version is part of the Arduino GLCD library. 6 | * 7 | * This file is based on code by Copyright Hans-Juergen Heinrichs (c) 2005 8 | * 9 | * the following comment is from his file 10 | * The idea for the functions below was heavily inspired by the 11 | * file which is part of the excellent WinAVR 12 | * distribution. Therefore, thanks to Marek Michalkiewicz and 13 | * Joerg Wunsch. 14 | * 15 | * The idea is to have the GCC preprocessor handle all calculations 16 | * necessary for determining the exact implementation of a delay 17 | * algorithm. The implementation itself is then inlined into the 18 | * user code. 19 | * In this way it is possible to always get the code size optimized 20 | * delay implementation. 21 | * 22 | */ 23 | 24 | /* 25 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 26 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 27 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 28 | ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 29 | LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 30 | CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 31 | SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 32 | INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 33 | CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 34 | ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 35 | POSSIBILITY OF SUCH DAMAGE. 36 | */ 37 | 38 | 39 | #ifndef _ARDUINO_DELAY_H_ 40 | #define _ARDUINO_DELAY_H_ 41 | 42 | #include 43 | 44 | #ifndef F_CPU 45 | # warning "Macro F_CPU must be defined" 46 | #endif 47 | 48 | /* 49 | * Forward declaration for all functions with attribute 50 | * 'always_inline' enforces GCC to inline the code (even 51 | * if it would be better not to do so from optimization 52 | * perspective). 53 | * Without this attribute GCC is free to implement 54 | * inline code or not (using the keyword 'inline' 55 | * alone is not sufficient). 56 | * 57 | */ 58 | static __inline__ void _NOP1( void) __attribute__((always_inline)); 59 | static __inline__ void _NOP2( void) __attribute__((always_inline)); 60 | static __inline__ void _NOP3( void) __attribute__((always_inline)); 61 | static __inline__ void _NOP4( void) __attribute__((always_inline)); 62 | static __inline__ void _NOP5( void) __attribute__((always_inline)); 63 | static __inline__ void _NOP6( void) __attribute__((always_inline)); 64 | static __inline__ void _NOP7( void) __attribute__((always_inline)); 65 | static __inline__ void _NOP8( void) __attribute__((always_inline)); 66 | static __inline__ void _NOP9( void) __attribute__((always_inline)); 67 | static __inline__ void _NOP10(void) __attribute__((always_inline)); 68 | static __inline__ void _NOP11(void) __attribute__((always_inline)); 69 | static __inline__ void _NOP12(void) __attribute__((always_inline)); 70 | 71 | static __inline__ void _delay_loop_3( uint32_t) __attribute__((always_inline)); 72 | static __inline__ void _delay_loop_1_x( uint8_t) __attribute__((always_inline)); 73 | static __inline__ void _delay_loop_2_x(uint16_t) __attribute__((always_inline)); 74 | static __inline__ void _delay_loop_3_x(uint32_t) __attribute__((always_inline)); 75 | 76 | static __inline__ void _delay_cycles(const double) __attribute__((always_inline)); 77 | 78 | 79 | /* 80 | * _ N O P x ( void ) 81 | * 82 | * Code sized optimized NOPs - not using any registers 83 | * 84 | * These NOPs will be used for very short delays where 85 | * it is more code efficient than executing loops. 86 | * 87 | */ 88 | static __inline__ void _NOP1 (void) { __asm__ volatile ( "nop " "\n\t" ); } 89 | static __inline__ void _NOP2 (void) { __asm__ volatile ( "rjmp 1f" "\n\t" "1:" "\n\t" ); } 90 | static __inline__ void _NOP3 (void) { __asm__ volatile ( "lpm " "\n\t" ); } 91 | static __inline__ void _NOP4 (void) { _NOP3(); _NOP1(); } 92 | static __inline__ void _NOP5 (void) { _NOP3(); _NOP2(); } 93 | static __inline__ void _NOP6 (void) { _NOP3(); _NOP3(); } 94 | static __inline__ void _NOP7 (void) { _NOP3(); _NOP3(); _NOP1(); } 95 | static __inline__ void _NOP8 (void) { _NOP3(); _NOP3(); _NOP2(); } 96 | static __inline__ void _NOP9 (void) { _NOP3(); _NOP3(); _NOP3(); } 97 | static __inline__ void _NOP10(void) { _NOP3(); _NOP3(); _NOP3(); _NOP1(); } 98 | static __inline__ void _NOP11(void) { _NOP3(); _NOP3(); _NOP3(); _NOP2(); } 99 | static __inline__ void _NOP12(void) { _NOP3(); _NOP3(); _NOP3(); _NOP3(); } 100 | 101 | 102 | 103 | /* 104 | * _ d e l a y _ l o o p _ 3( uint32_t __count ) 105 | * 106 | * This delay loop is not used in the code below: It is 107 | * a supplement to the _delay_loop_1() and _delay_loop_2() 108 | * within standard WinAVR giving a wider 109 | * (32 bit) delay range. 110 | * 111 | */ 112 | static __inline__ void 113 | _delay_loop_3( uint32_t __count ) 114 | { 115 | __asm__ volatile ( 116 | "1: sbiw %A0,1" "\n\t" 117 | "sbc %C0,__zero_reg__" "\n\t" 118 | "sbc %D0,__zero_reg__" "\n\t" 119 | "brne 1b" 120 | : "=w" (__count) 121 | : "0" (__count) 122 | ); 123 | } 124 | 125 | 126 | /* 127 | * _ d e l a y _ l o o p _ 1 _ x( uint8_t __count ) 128 | * _ d e l a y _ l o o p _ 2 _ x( uint16_t __count ) 129 | * _ d e l a y _ l o o p _ 4 _ x( uint32_t __count ) 130 | * 131 | * These delay loops always have exactly 4(8) cycles per loop. 132 | * They use a 8/16/32 bit register counter respectively. 133 | * 134 | */ 135 | static __inline__ void /* exactly 4 cycles/loop, max 2**8 loops */ 136 | _delay_loop_1_x( uint8_t __n ) 137 | { /* cycles per loop */ 138 | __asm__ volatile ( /* __n..one zero */ 139 | "1: dec %0" "\n\t" /* 1 1 */ 140 | " breq 2f" "\n\t" /* 1 2 */ 141 | "2: brne 1b" "\n\t" /* 2 1 */ 142 | : "=r" (__n) /* ----- ----- */ 143 | : "0" (__n) /* 4 4 */ 144 | ); 145 | } 146 | 147 | static __inline__ void /* exactly 4 cycles/loop, max 2**16 loops */ 148 | _delay_loop_2_x( uint16_t __n ) 149 | { /* cycles per loop */ 150 | __asm__ volatile ( /* __n..one zero */ 151 | "1: sbiw %0,1" "\n\t" /* 2 2 */ 152 | " brne 1b " "\n\t" /* 2 1 */ 153 | " nop " "\n\t" /* 1 */ 154 | : "=w" (__n) /* ----- ----- */ 155 | : "0" (__n) /* 4 4 */ 156 | ); 157 | } 158 | 159 | static __inline__ void /* exactly 8 cycles/loop, max 2**32 loops */ 160 | _delay_loop_3_x( uint32_t __n ) 161 | { /* cycles per loop */ 162 | __asm__ volatile ( /* __n..one zero */ 163 | "1: sbiw %A0,1 " "\n\t" /* 2 2 */ 164 | " sbc %C0,__zero_reg__" "\n\t" /* 1 1 */ 165 | " sbc %D0,__zero_reg__" "\n\t" /* 1 1 */ 166 | " nop " "\n\t" /* 1 1 */ 167 | " breq 2f " "\n\t" /* 1 2 */ 168 | "2: brne 1b " "\n\t" /* 2 1 */ 169 | : "=w" (__n) /* ----- ----- */ 170 | : "0" (__n) /* 8 8 */ 171 | ); 172 | } 173 | 174 | 175 | /* 176 | * 177 | * _ d e l a y _ c y c l e s (double __ticks_d) 178 | * 179 | * Perform an accurate delay of a given number of processor cycles. 180 | * 181 | * All the floating point arithmetic will be handled by the 182 | * GCC Preprocessor and no floating point code will be generated. 183 | * Allthough the parameter __ticks_d is of type 'double' this 184 | * function can be called with any constant integer value, too. 185 | * GCC will handle the casting appropriately. 186 | * 187 | * With an 8 MHz clock e.g., delays ranging from 125 nanoseconds 188 | * up to (2**32-1) * 125ns ~= 536,87 seconds are feasible. 189 | * 190 | */ 191 | static __inline__ void 192 | _delay_cycles(const double __ticks_d) 193 | { 194 | uint32_t __ticks = (uint32_t)(__ticks_d); 195 | uint32_t __padding; 196 | uint32_t __loops; 197 | 198 | /* 199 | * Special optimization for very 200 | * small delays - not using any register. 201 | */ 202 | if( __ticks <= 12 ) { /* this can be done with 4 opcodes */ 203 | __padding = __ticks; 204 | 205 | /* create a single byte counter */ 206 | } else if( __ticks <= 0x400 ) { 207 | __ticks -= 1; /* caller needs 1 cycle to init counter */ 208 | __loops = __ticks / 4; 209 | __padding = __ticks % 4; 210 | if( __loops != 0 ) 211 | _delay_loop_1_x( (uint8_t)__loops ); 212 | 213 | /* create a two byte counter */ 214 | } else if( __ticks <= 0x40001 ) { 215 | __ticks -= 2; /* caller needs 2 cycles to init counter */ 216 | __loops = __ticks / 4; 217 | __padding = __ticks % 4; 218 | if( __loops != 0 ) 219 | _delay_loop_2_x( (uint16_t)__loops ); 220 | 221 | /* create a four byte counter */ 222 | } else { 223 | __ticks -= 4; /* caller needs 4 cycles to init counter */ 224 | __loops = __ticks / 8; 225 | __padding = __ticks % 8; 226 | if( __loops != 0 ) 227 | _delay_loop_3_x( (uint32_t)__loops ); 228 | } 229 | 230 | if( __padding == 1 ) _NOP1(); 231 | if( __padding == 2 ) _NOP2(); 232 | if( __padding == 3 ) _NOP3(); 233 | if( __padding == 4 ) _NOP4(); 234 | if( __padding == 5 ) _NOP5(); 235 | if( __padding == 6 ) _NOP6(); 236 | if( __padding == 7 ) _NOP7(); 237 | if( __padding == 8 ) _NOP8(); 238 | if( __padding == 9 ) _NOP9(); 239 | if( __padding == 10 ) _NOP10(); 240 | if( __padding == 11 ) _NOP11(); 241 | if( __padding == 12 ) _NOP12(); 242 | } 243 | 244 | 245 | /* 246 | * _ d e l a y _ n s (double __ns) 247 | * _ d e l a y _ u s (double __us) 248 | * 249 | * Perform a very exact delay with a resolution as accurate as a 250 | * single CPU clock (the macro F_CPU is supposed to be defined to a 251 | * constant defining the CPU clock frequency in Hertz). 252 | * 253 | */ 254 | #define _delayNanoseconds(__ns) _delay_cycles( (double)(F_CPU)*((double)__ns)/1.0e9 + 0.5 ) 255 | #define _delayMicroseconds(__us) _delay_cycles( (double)(F_CPU)*((double)__us)/1.0e12 + 0.5 ) 256 | #define _delayMilliseconds(__ms) _delay_cycles( (double)(F_CPU)*((double)__ms)/1.0e15 + 0.5 ) 257 | 258 | #endif /* _ARDUINO_DELAY_H_ */ 259 | -------------------------------------------------------------------------------- /arduvision_01/arduino/ov_fifo_test/fifo.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "fifo.h" 3 | 4 | 5 | void fifo_loadFrame(void) 6 | { 7 | fifo_wrst(); 8 | // Capture frame 9 | // VSYNC is supposed to be set positive in the ov7725 (reg REG_COM10) 10 | while (!GET_VSYNC); // wait for an old frame to end 11 | while (GET_VSYNC); // wait for a new frame to start 12 | ENABLE_WREN; // enable writing to fifo 13 | while (!GET_VSYNC); // wait for the current frame to end 14 | DISABLE_WREN; // disable writing to fifo 15 | //wait(); 16 | DISABLE_RRST; 17 | } 18 | 19 | 20 | // Reset the fifo read pointer 21 | void fifo_rrst(void) 22 | { 23 | ENABLE_RRST; 24 | //_delayNanoseconds(5); 25 | SET_RCLK_H; 26 | //_delayNanoseconds(5); 27 | SET_RCLK_L; 28 | DISABLE_RRST; 29 | } 30 | //************************** 31 | 32 | // Reset the fifo write pointer 33 | void fifo_wrst(void) 34 | { 35 | DISABLE_WREN; 36 | _delayMicroseconds(1); 37 | ENABLE_WRST; 38 | _delayMicroseconds(1); 39 | DISABLE_WRST; 40 | } 41 | //************************** 42 | 43 | // Read one byte from the fifo 44 | uint8_t fifo_readByte(void) 45 | { 46 | uint8_t val; 47 | SET_RCLK_H; 48 | val = DATA_PINS; 49 | //_delay_cycles(10); 50 | SET_RCLK_L; 51 | //_delay_cycles(10); 52 | 53 | return val; 54 | } 55 | 56 | //************************** 57 | // 58 | // 59 | //************************** 60 | uint8_t fifo_readBytes(uint8_t *destBuf, unsigned long nBytes) 61 | { 62 | uint8_t *bufIndex = destBuf; 63 | 64 | while (nBytes > 0) { 65 | SET_RCLK_H; 66 | *bufIndex = DATA_PINS; 67 | //_delay_cycles(10); 68 | SET_RCLK_L; 69 | //_delay_cycles(10); 70 | bufIndex++; 71 | nBytes--; 72 | } 73 | return (nBytes == 0); 74 | } 75 | 76 | 77 | //************************** 78 | 79 | void fifo_sendSerialBytes(Stream &destPort, unsigned long nBytes) { 80 | 81 | uint8_t oneByte; 82 | // passing the serial por (Stream type) as a pointer would save memory ??? 83 | while (nBytes > 0) { 84 | // faster than passing the fifo_readByte() function to write() 85 | oneByte = fifo_readByte(); 86 | destPort.write(oneByte); //print((char)ov7725_read()); 87 | nBytes--; 88 | } 89 | } 90 | -------------------------------------------------------------------------------- /arduvision_01/arduino/ov_fifo_test/fifo.h: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include "IO_config.h" 4 | #include "delay.h" 5 | 6 | void fifo_loadFrame(void); 7 | 8 | void fifo_rrst(void); 9 | void fifo_wrst(void); 10 | uint8_t fifo_readByte(void); 11 | void fifo_readStop(void); 12 | 13 | uint8_t fifo_readBytes(uint8_t *destBuf, unsigned long nBytes); 14 | 15 | void fifo_sendSerialBytes(Stream &destPort, unsigned long nBytes); 16 | 17 | // -------------------------------------- 18 | void __inline__ fifo_skipBytes(unsigned long nBytes) 19 | { 20 | while (nBytes > 0) { 21 | SET_RCLK_H; 22 | _delay_cycles(10); 23 | SET_RCLK_L; 24 | _delay_cycles(10); 25 | nBytes--; 26 | } 27 | } 28 | // -------------------------------------- 29 | static __inline__ void fifo_readRow0ppb(uint8_t* _rowStart, uint8_t* _rowEnd) 30 | { 31 | while (_rowStart != _rowEnd) { 32 | SET_RCLK_H; 33 | *_rowStart++ = DATA_PINS; 34 | //_delayNanoseconds(5); 35 | SET_RCLK_L; 36 | //_delayNanoseconds(5); 37 | } 38 | } 39 | // -------------------------------------- 40 | static __inline__ void fifo_readRow1ppb(uint8_t* _rowStart, uint8_t* _rowEnd) 41 | { 42 | while (_rowStart != _rowEnd) { 43 | SET_RCLK_H; 44 | *_rowStart = DATA_PINS >> 4; 45 | //_delayNanoseconds(5); 46 | SET_RCLK_L; 47 | //_delayNanoseconds(5); 48 | SET_RCLK_H; 49 | *_rowStart++ |= DATA_PINS & 0xf0; 50 | //_delayNanoseconds(5); 51 | SET_RCLK_L; 52 | //_delayNanoseconds(5); 53 | } 54 | } 55 | // -------------------------------------- 56 | static __inline__ void fifo_readRow2ppb(uint8_t* _rowStart, uint8_t* _rowEnd) 57 | { 58 | uint8_t pixValue = 0; 59 | uint8_t dataValue = 0; 60 | while (_rowStart != _rowEnd) { 61 | 62 | SET_RCLK_H; 63 | pixValue = DATA_PINS >> 4; 64 | SET_RCLK_L; 65 | 66 | SET_RCLK_H; 67 | SET_RCLK_L; 68 | 69 | SET_RCLK_H; 70 | pixValue |= (DATA_PINS & 0xF0); 71 | SET_RCLK_L; 72 | 73 | SET_RCLK_H; 74 | SET_RCLK_L; 75 | 76 | *_rowStart++ = pixValue; 77 | } 78 | } 79 | // -------------------------------------- 80 | static __inline__ void fifo_readRow4ppb(uint8_t* _rowStart, uint8_t* _rowEnd) 81 | { 82 | uint8_t pixValue = 0; 83 | uint8_t dataValue = 0; 84 | while (_rowStart != _rowEnd) { 85 | 86 | SET_RCLK_H; 87 | pixValue = DATA_PINS >> 6; 88 | SET_RCLK_L; 89 | 90 | SET_RCLK_H; 91 | SET_RCLK_L; 92 | 93 | SET_RCLK_H; 94 | pixValue |= (DATA_PINS & 0xC0) >> 4; 95 | SET_RCLK_L; 96 | 97 | SET_RCLK_H; 98 | SET_RCLK_L; 99 | 100 | SET_RCLK_H; 101 | pixValue |= (DATA_PINS & 0xC0) >> 2; 102 | SET_RCLK_L; 103 | 104 | SET_RCLK_H; 105 | SET_RCLK_L; 106 | 107 | SET_RCLK_H; 108 | pixValue |= DATA_PINS & 0xC0; 109 | SET_RCLK_L; 110 | 111 | SET_RCLK_H; 112 | SET_RCLK_L; 113 | 114 | *_rowStart++ = pixValue; 115 | } 116 | } 117 | // -------------------------------------- 118 | static __inline__ void fifo_readRow8ppb(uint8_t* _rowStart, uint8_t* _rowEnd, uint8_t thresh) 119 | { 120 | uint8_t pixValue = 0; 121 | uint8_t bitIndex = 0; 122 | 123 | while (_rowStart != _rowEnd ) { 124 | //read "Y" byte 125 | SET_RCLK_H; 126 | pixValue |= (((DATA_PINS & 0xF8) > thresh) << bitIndex); 127 | SET_RCLK_L; 128 | 129 | // skip "U/V" byte 130 | SET_RCLK_H; 131 | SET_RCLK_L; 132 | bitIndex++; 133 | if (bitIndex == 8) { 134 | *_rowStart++ = pixValue; 135 | bitIndex = 0; 136 | pixValue = 0; 137 | } 138 | 139 | } 140 | } 141 | // -------------------------------------------- 142 | // -------------------------------------------- 143 | static __inline__ void fifo_getBrig(uint8_t* _rowStart, uint8_t _frW, uint8_t _frH, uint8_t _border, uint8_t _thresh) 144 | { 145 | 146 | } 147 | // -------------------------------------------- 148 | static __inline__ void fifo_getDark(uint8_t* _rowStart, uint8_t _frW, uint8_t _frH, uint8_t _border, uint8_t _thresh) 149 | { 150 | uint8_t i = 0; 151 | uint8_t j = 0; 152 | uint8_t pix = 255; 153 | uint8_t x0 = 255; 154 | uint8_t y0 = 255; 155 | uint8_t x1 = 0; 156 | uint8_t y1 = 0; 157 | uint8_t skipBytesX = _border * 2 ; // BPP 158 | uint8_t skipBytesX2 = skipBytesX * 2 + 2; 159 | uint16_t skipBytesY = (_border * _frW) * 2; // BPP 160 | 161 | _frH -= _border; 162 | _frW -= _border+1; 163 | 164 | fifo_skipBytes(skipBytesY); 165 | fifo_skipBytes(skipBytesX); 166 | for (j =_border; j < _frH; j++) { 167 | for (i =_border; i < _frW; i++) { 168 | // Y value of Nth pixel 169 | SET_RCLK_H; 170 | pix = DATA_PINS; 171 | SET_RCLK_L; 172 | if (pix < _thresh) { 173 | if (i > x1) x1 = i; 174 | else if (i < x0) x0 = i; 175 | if (y0 == 255) y0 = j; // first time only, y0 = 255 176 | y1 = j; 177 | } 178 | // skip "U/v" byte 179 | SET_RCLK_H; 180 | _delayNanoseconds(5); 181 | SET_RCLK_L; 182 | _delayNanoseconds(5); 183 | } 184 | fifo_skipBytes(skipBytesX2); 185 | } 186 | 187 | if ( (x0 < x1 ) && (y0 < y1 ) ) { 188 | *_rowStart++ = x0; 189 | *_rowStart++ = y0; 190 | *_rowStart++ = x1; 191 | *_rowStart++ = y1; 192 | } 193 | } 194 | // -------------------------------------- 195 | static __inline__ void fifo_loadFrameFast(void) 196 | { 197 | DISABLE_WREN; // disable writing to fifo 198 | 199 | ENABLE_WRST; 200 | //_delayNanoseconds(5); 201 | SET_RCLK_H; 202 | //_delayNanoseconds(5); 203 | SET_RCLK_L; 204 | DISABLE_WRST; 205 | _delay_cycles(10); 206 | while (!GET_VSYNC); // wait for an old frame to end 207 | while (GET_VSYNC); // wait for a new frame to start 208 | 209 | ENABLE_WREN; // enable writing to fifo 210 | while (!GET_VSYNC); // wait for the current frame to end 211 | 212 | ENABLE_RRST; 213 | //_delayNanoseconds(5); 214 | SET_RCLK_H; 215 | //_delayNanoseconds(5); 216 | SET_RCLK_L; 217 | DISABLE_RRST; 218 | } 219 | 220 | 221 | 222 | -------------------------------------------------------------------------------- /arduvision_01/arduino/ov_fifo_test/ov7670_regs.h: -------------------------------------------------------------------------------- 1 | /* 2 | * A V4L2 driver for OmniVision OV7670 cameras. 3 | * 4 | * Copyright 2006 One Laptop Per Child Association, Inc. Written 5 | * by Jonathan Corbet with substantial inspiration from Mark 6 | * McClelland's ovcamchip code. 7 | * 8 | * Copyright 2006-7 Jonathan Corbet 9 | * 10 | * This file may be distributed under the terms of the GNU General 11 | * Public License, version 2. 12 | 13 | * Aug 18, 2014 - Adapted by David Sanz Kirbis: 14 | */ 15 | 16 | 17 | 18 | #ifndef _OV7670_REGS_H 19 | #define _OV7670_REGS_H 20 | 21 | 22 | #include 23 | #include 24 | #include "sensor.h" 25 | 26 | 27 | #define OV7670_RD_ADDR 0x42 28 | #define OV7670_WR_ADDR 0x43 29 | 30 | #define VGA_WIDTH 640 31 | #define VGA_HEIGHT 480 32 | #define QVGA_WIDTH 320 33 | #define QVGA_HEIGHT 240 34 | #define QQVGA_WIDTH 160 35 | #define QQVGA_HEIGHT 120 36 | #define QQQVGA_WIDTH 80 37 | #define QQQVGA_HEIGHT 60 38 | #define CIF_WIDTH 352 39 | #define CIF_HEIGHT 288 40 | #define QCIF_WIDTH 176 41 | #define QCIF_HEIGHT 144 42 | 43 | 44 | // Control 1 45 | #define OV7670_REG_COM7 0x12 // Control 7 46 | #define COM7_RESET 0x80 // Register reset 47 | #define COM7_FMT_MASK 0x38 48 | #define COM7_FMT_VGA 0x00 49 | #define COM7_FMT_CIF 0x20 // CIF format 50 | #define COM7_FMT_QVGA 0x10 // QVGA format 51 | #define COM7_FMT_QCIF 0x08 // QCIF format 52 | #define COM7_RGB 0x04 // bits 0 and 2 - RGB format 53 | #define COM7_YUV 0x00 // YUV 54 | #define COM7_BAYER 0x01 // Bayer format 55 | #define COM7_PBAYER 0x05 // "Processed bayer" 56 | #define OV7670_REG_RGB444 0x8c // RGB 444 control 57 | #define R444_DISABLE 0x00 // Turn on RGB444, overrides 5x5 58 | #define R444_ENABLE 0x02 // Turn on RGB444, overrides 5x5 59 | #define R444_RGBX 0x01 // Empty nibble at end 60 | #define OV7670_REG_COM9 0x14 // Control 9 - gain ceiling 61 | #define OV7670_REG_COM10 0x15 // Control 10 62 | #define OV7670_REG_COM13 0x3d // Control 13 63 | #define COM13_GAMMA 0x80 // Gamma enable 64 | #define COM13_UVSAT 0x40 // UV saturation auto adjustment 65 | #define COM13_UVSWAP 0x01 // V before U - w/TSLB 66 | #define OV7670_REG_COM15 0x40 // Control 15 67 | #define COM15_R10F0 0x00 // Data range 10 to F0 68 | #define COM15_R01FE 0x80 // 01 to FE 69 | #define COM15_R00FF 0xc0 // 00 to FF 70 | #define COM15_RGB565 0x10 // RGB565 output 71 | #define COM15_RGB555 0x30 // RGB555 output 72 | #define OV7670_REG_COM11 0x3b // Control 11 73 | #define COM11_NIGHT 0x80 // NIght mode enable 74 | #define COM11_NMFR 0x60 // Two bit NM frame rate 75 | #define COM11_HZAUTO 0x10 // Auto detect 50/60 Hz 76 | #define COM11_50HZ 0x08 // Manual 50Hz select 77 | #define COM11_EXP 0x02 78 | #define OV7670_REG_COM17 0x42 // Control 17 79 | #define COM17_AECWIN 0xc0 // AEC window - must match COM4 80 | #define COM17_CBAR 0x08 // DSP Color bar 81 | #define OV7670_REG_TSLB 0x3a // lots of stuff 82 | #define TSLB_YLAST 0x04 // UYVY or VYUY - see com13 83 | #define TSLB_AUTO_OW 0x01 // Sensor automatically sets output window when resolution changes 84 | #define MTX1 0x4f // Matrix Coefficient 1 85 | #define MTX2 0x50 // Matrix Coefficient 2 86 | #define MTX3 0x51 // Matrix Coefficient 3 87 | #define MTX4 0x52 // Matrix Coefficient 4 88 | #define MTX5 0x53 // Matrix Coefficient 5 89 | #define MTX6 0x54 // Matrix Coefficient 6 90 | #define OV7670_REG_CONTRAS 0x56 // Contrast control 91 | #define MTXS 0x58 // Matrix Coefficient Sign 92 | #define AWBC7 0x59 // AWB Control 7 93 | #define AWBC8 0x5a // AWB Control 8 94 | #define AWBC9 0x5b // AWB Control 9 95 | #define AWBC10 0x5c // AWB Control 10 96 | #define AWBC11 0x5d // AWB Control 11 97 | #define AWBC12 0x5e // AWB Control 12 98 | #define OV7670_REG_GFIX 0x69 // Fix gain control 99 | #define GGAIN 0x6a // G Channel AWB Gain 100 | #define OV7670_REG_DBLV 0x6b // PLL control & internal regulator ( reg = on ) 101 | #define DBLV_X0 0x0A // Bypass PLL 102 | #define DBLV_X4 0x4A // Input clock x4 103 | #define DBLV_X6 0x8A // Input clock x6 104 | #define DBLV_X8 0xCA // Input clock x8 105 | #define AWBCTR3 0x6c // AWB Control 3 106 | #define AWBCTR2 0x6d // AWB Control 2 107 | #define AWBCTR1 0x6e // AWB Control 1 108 | #define AWBCTR0 0x6f // AWB Control 0 109 | #define OV7670_REG_COM8 0x13 // Control 8 110 | #define COM8_FASTAEC 0x80 // Enable fast AGC/AEC 111 | #define COM8_AECSTEP 0x40 // Unlimited AEC step size 112 | #define COM8_BFILT 0x20 // Band filter enable 113 | #define COM8_AGC 0x04 // Auto gain enable 114 | #define COM8_AWB 0x02 // White balance enable 115 | #define COM8_AEC 0x01 // Auto exposure enable 116 | #define OV7670_REG_COM3 0x0c // Control 3 117 | #define COM3_SWAP 0x40 // Byte swap 118 | #define COM3_SCALEEN 0x08 // Enable scaling 119 | #define COM3_DCWEN 0x04 // Enable downsamp/crop/window 120 | #define OV7670_REG_BRIGHT 0x55 // Brightness 121 | #define OV7670_REG_COM14 0x3e // Control 14 122 | #define COM14_DCWEN 0x10 // DCW/PCLK-scale enable 123 | #define COM14_PCLK_1 0x00 // PCLK Divided by 1 124 | #define COM14_PCLK_2 0x01 // PCLK Divided by 2 125 | #define COM14_PCLK_4 0x02 // PCLK Divided by 4 126 | #define COM14_PCLK_8 0x03 // PCLK Divided by 8 127 | #define COM14_PCLK_16 0x04 // PCLK Divided by 16 128 | #define OV7670_REG_HSTART 0x17 // Horiz start high bits 129 | #define OV7670_REG_HSTOP 0x18 // Horiz stop high bits 130 | #define OV7670_REG_VSTART 0x19 // Vert start high bits 131 | #define OV7670_REG_VSTOP 0x1a // Vert stop high bits 132 | #define OV7670_REG_HREF 0x32 // HREF pieces 133 | #define OV7670_REG_VREF 0x03 // Pieces of GAIN, VSTART, VSTOP 134 | // Registers 135 | #define OV7670_REG_GAIN 0x00 // Gain lower 8 bits (rest in vref) 136 | #define OV7670_REG_BLUE 0x01 // blue gain 137 | #define OV7670_REG_RED 0x02 // red gain 138 | #define OV7670_REG_VREF 0x03 // Pieces of GAIN, VSTART, VSTOP 139 | #define OV7670_REG_COM1 0x04 // Control 1 140 | #define COM1_CCIR656 0x40 // CCIR656 enable 141 | #define OV7670_REG_BAVE 0x05 // U/B Average level 142 | #define OV7670_REG_GbAVE 0x06 // Y/Gb Average level 143 | #define OV7670_REG_AECHH 0x07 // AEC MS 5 bits 144 | #define OV7670_REG_RAVE 0x08 // V/R Average level 145 | #define OV7670_REG_COM2 0x09 // Control 2 146 | #define COM2_SSLEEP 0x10 // Soft sleep mode 147 | #define OV7670_REG_PID 0x0a // Product ID MSB 148 | #define OV7670_REG_VER 0x0b // Product ID LSB 149 | #define OV7670_REG_COM3 0x0c // Control 3 150 | #define COM3_SWAP 0x40 // Byte swap 151 | #define COM3_SCALEEN 0x08 // Enable scaling 152 | #define COM3_DCWEN 0x04 // Enable downsamp/crop/window 153 | #define OV7670_REG_COM4 0x0d // Control 4 154 | #define OV7670_REG_COM5 0x0e // All "reserved" 155 | #define OV7670_REG_COM6 0x0f // Control 6 156 | #define OV7670_REG_AECH 0x10 // More bits of AEC value 157 | #define OV7670_REG_CLKRC 0x11 // Clocl control 158 | #define CLK_EXT 0x40 // Use external clock directly 159 | #define CLKRC_0 0x00 160 | #define CLKRC_2 0x01 // internal clock / 2 161 | #define CLKRC_3 0x02 // internal clock / 3 162 | #define CLKRC_4 0x03 // internal clock / 4 163 | #define CLKRC_5 0x04 // internal clock / 5 164 | #define CLKRC_6 0x05 // internal clock / 5 165 | #define CLK_SCALE 0x3f // Mask for internal clock scale 166 | #define OV7670_REG_COM7 0x12 // Control 7 167 | #define COM7_RESET 0x80 // Register reset 168 | #define COM7_FMT_MASK 0x38 169 | #define COM7_FMT_VGA 0x00 170 | #define COM7_FMT_CIF 0x20 // CIF format 171 | #define COM7_FMT_QVGA 0x10 // QVGA format 172 | #define COM7_FMT_QCIF 0x08 // QCIF format 173 | #define COM7_RGB 0x04 // bits 0 and 2 - RGB format 174 | #define COM7_YUV 0x00 // YUV 175 | #define COM7_BAYER 0x01 // Bayer format 176 | #define COM7_PBAYER 0x05 // "Processed bayer" 177 | #define OV7670_REG_COM8 0x13 // Control 8 178 | #define COM8_FASTAEC 0x80 // Enable fast AGC/AEC 179 | #define COM8_AECSTEP 0x40 // Unlimited AEC step size 180 | #define COM8_BFILT 0x20 // Band filter enable 181 | #define COM8_AGC 0x04 // Auto gain enable 182 | #define COM8_AWB 0x02 // White balance enable 183 | #define COM8_AEC 0x01 // Auto exposure enable 184 | #define OV7670_REG_COM9 0x14 // Control 9 - gain ceiling 185 | #define OV7670_REG_COM10 0x15 // Control 10 186 | #define COM10_HSYNC 0x40 // HSYNC instead of HREF 187 | #define COM10_PCLK_HB 0x20 // Suppress PCLK on horiz blank 188 | #define COM10_HREF_REV 0x08 // Reverse HREF 189 | #define COM10_VS_LEAD 0x04 // VSYNC on clock leading edge 190 | #define COM10_VS_NEG 0x02 // VSYNC negative 191 | #define COM10_HS_NEG 0x01 // HSYNC negative 192 | #define OV7670_REG_HSTART 0x17 // Horiz start high bits 193 | #define OV7670_REG_HSTOP 0x18 // Horiz stop high bits 194 | #define OV7670_REG_VSTART 0x19 // Vert start high bits 195 | #define OV7670_REG_VSTOP 0x1a // Vert stop high bits 196 | #define OV7670_REG_PSHFT 0x1b // Pixel delay after HREF 197 | #define OV7670_REG_MIDH 0x1c // Manuf. ID high 198 | #define OV7670_REG_MIDL 0x1d // Manuf. ID low 199 | #define OV7670_REG_MVFP 0x1e // Mirror / vflip 200 | #define MVFP_MIRROR 0x20 // Mirror image 201 | #define MVFP_FLIP 0x10 // Vertical flip 202 | 203 | #define OV7670_REG_AEW 0x24 // AGC upper limit 204 | #define OV7670_REG_AEB 0x25 // AGC lower limit 205 | #define OV7670_REG_VPT 0x26 // AGC/AEC fast mode op region 206 | #define OV7670_REG_HSYST 0x30 // HSYNC rising edge delay 207 | #define OV7670_REG_HSYEN 0x31 // HSYNC falling edge delay 208 | #define OV7670_REG_HREF 0x32 // HREF pieces 209 | #define OV7670_REG_TSLB 0x3a // lots of stuff 210 | #define TSLB_YLAST 0x04 // UYVY or VYUY - see com13 211 | #define TSLB_AUTO_OW 0x01 // Sensor automatically sets output window when resolution changes 212 | #define OV7670_REG_COM11 0x3b // Control 11 213 | #define COM11_NIGHT 0x80 // NIght mode enable 214 | #define COM11_NMFR 0x60 // Two bit NM frame rate 215 | #define COM11_HZAUTO 0x10 // Auto detect 50/60 Hz 216 | #define COM11_50HZ 0x08 // Manual 50Hz select 217 | #define COM11_EXP 0x02 218 | #define OV7670_REG_COM12 0x3c // Control 12 219 | #define COM12_HREF 0x80 // HREF always 220 | #define OV7670_REG_COM13 0x3d // Control 13 221 | #define COM13_GAMMA 0x80 // Gamma enable 222 | #define COM13_UVSAT 0b11001000 // UV saturation auto adjustment 223 | #define COM13_UVSWAP 0x01 // V before U - w/TSLB 224 | #define COM13_RSVD 0x08 225 | #define OV7670_REG_COM14 0x3e // Control 14 226 | #define COM14_DCWEN 0x10 // DCW/PCLK-scale enable 227 | #define COM14_DCW_MSCL 0x08 // Manual scaling 228 | #define COM14_PCLK_DIV_2 0x01 // divide pclk by 2 229 | #define COM14_PCLK_DIV_4 0x02 // divide pclk by 4 230 | #define COM14_PCLK_DIV_8 0x03 // divide pclk by 8 231 | #define COM14_PCLK_DIV_16 0x04 // divide pclk by 16 232 | 233 | #define OV7670_REG_EDGE 0x3f // Edge enhancement factor 234 | #define OV7670_REG_COM15 0x40 // Control 15 235 | #define COM15_R10F0 0x00 // Data range 10 to F0 236 | #define COM15_R01FE 0x80 // 01 to FE 237 | #define COM15_R00FF 0xc0 // 00 to FF 238 | #define COM15_RGB565 0x10 // RGB565 output 239 | #define COM15_RGB555 0x30 // RGB555 output 240 | #define OV7670_REG_COM16 0x41 // Control 16 241 | #define COM16_AWBGAIN 0x08 // AWB gain enable 242 | #define OV7670_REG_COM17 0x42 // Control 17 243 | #define COM17_AECWIN 0xc0 // AEC window - must match COM4 244 | #define COM17_CBAR 0x08 // DSP Color bar 245 | 246 | #define OV7670_REG_SCALING_XSC 0x70 // Bit[6:0]: Horizontal scale factor, def 3A 247 | #define OV7670_REG_SCALING_YSC 0x71 // Bit[6:0]: Vertical scale factor, def 35 248 | 249 | 250 | #define OV7670_REG_SCALING_DCWCTR 0x72 251 | #define SCALING_DCWCTR_2 0x11 // downsample by 2 252 | #define SCALING_DCWCTR_4 0x22 // downsample by 4 253 | #define SCALING_DCWCTR_8 0x33 // downsample by 8 254 | 255 | #define OV7670_REG_SCALING_PCLK_DIV 0x73 256 | #define SCALING_PCLK_DIV_1 0x00 257 | #define SCALING_PCLK_DIV_2 0x01 258 | #define SCALING_PCLK_DIV_4 0x02 259 | #define SCALING_PCLK_DIV_8 0x03 260 | #define SCALING_PCLK_DIV_16 0x04 261 | 262 | #define OV7670_REG_SCALING_PCLK_DELAY 0xA2 // Bit[6:0]: Scaling output delay, def 0x02 263 | 264 | #define OV7670_REG_SATCTR 0xC9 265 | 266 | 267 | /* 268 | * This matrix defines how the colors are generated, must be 269 | * tweaked to adjust hue and saturation. 270 | * 271 | * Order: v-red, v-green, v-blue, u-red, u-green, u-blue 272 | * 273 | * They are nine-bit signed quantities, with the sign bit 274 | * stored in 0x58. Sign for v-red is bit 0, and up from there. 275 | */ 276 | #define OV7670_REG_CMATRIX_BASE 0x4f 277 | #define CMATRIX_LEN 6 278 | #define OV7670_REG_CMATRIX_SIGN 0x58 279 | 280 | 281 | #define OV7670_REG_BRIGHT 0x55 /* Brightness */ 282 | #define OV7670_REG_CONTRAS 0x56 /* Contrast control */ 283 | 284 | #define OV7670_REG_GFIX 0x69 /* Fix gain control */ 285 | 286 | #define OV7670_REG_REG76 0x76 /* OV's name */ 287 | #define R76_BLKPCOR 0x81 /* Black pixel correction enable */ 288 | #define R76_WHTPCOR 0x41 /* White pixel correction enable */ 289 | 290 | #define OV7670_REG_RGB444 0x8c /* RGB 444 control */ 291 | #define R444_ENABLE 0x02 /* Turn on RGB444, overrides 5x5 */ 292 | #define R444_RGBX 0x01 /* Empty nibble at end */ 293 | 294 | #define OV7670_REG_HAECC1 0x9f /* Hist AEC/AGC control 1 */ 295 | #define OV7670_REG_HAECC2 0xa0 /* Hist AEC/AGC control 2 */ 296 | 297 | #define OV7670_REG_BD50MAX 0xa5 /* 50hz banding step limit */ 298 | #define OV7670_REG_HAECC3 0xa6 /* Hist AEC/AGC control 3 */ 299 | #define OV7670_REG_HAECC4 0xa7 /* Hist AEC/AGC control 4 */ 300 | #define OV7670_REG_HAECC5 0xa8 /* Hist AEC/AGC control 5 */ 301 | #define OV7670_REG_HAECC6 0xa9 /* Hist AEC/AGC control 6 */ 302 | #define OV7670_REG_HAECC7 0xaa /* Hist AEC/AGC control 7 */ 303 | #define OV7670_REG_BD60MAX 0xab /* 60hz banding step limit */ 304 | 305 | 306 | const struct regval_list qqvga_yuv_ov7670[] PROGMEM = { 307 | 308 | {OV7670_REG_COM8, COM8_FASTAEC|COM8_AECSTEP|COM8_AGC|COM8_AEC|COM8_AWB }, 309 | 310 | {OV7670_REG_CLKRC, 0x80}, 311 | {OV7670_REG_COM11, 0x0A}, 312 | {OV7670_REG_COM7, 0x00}, // output format: yuv 313 | {OV7670_REG_COM15, 0xC0}, // 314 | 315 | // not even sure what all these do, gonna check the oscilloscope and go from there... 316 | {OV7670_REG_HSTART, 0x16}, 317 | {OV7670_REG_HSTOP, 0x04}, 318 | {OV7670_REG_HREF, 0x24}, 319 | {OV7670_REG_VSTART, 0x02}, 320 | {OV7670_REG_VSTOP, 0x7a}, 321 | {OV7670_REG_VREF, 0x0a}, 322 | {OV7670_REG_COM10, 0x02}, 323 | {OV7670_REG_COM3, 0x04}, 324 | {OV7670_REG_MVFP, 0x3f}, 325 | 326 | // 160x120 327 | {OV7670_REG_COM14, 0x1a}, // divide by 4 328 | {0x72, 0x22}, // downsample by 4 329 | {0x73, 0xf2}, // divide by 4 330 | 331 | // COLOR SETTING 332 | {0x4f, 0x80}, 333 | {0x50, 0x80}, 334 | {0x51, 0x00}, 335 | {0x52, 0x22}, 336 | {0x53, 0x5e}, 337 | {0x54, 0x80}, 338 | {0x56, 0x40}, 339 | {0x58, 0x9e}, 340 | {0x59, 0x88}, 341 | {0x5a, 0x88}, 342 | {0x5b, 0x44}, 343 | {0x5c, 0x67}, 344 | {0x5d, 0x49}, 345 | {0x5e, 0x0e}, 346 | {0x69, 0x00}, 347 | {0x6a, 0x40}, 348 | {0x6b, 0x0a}, 349 | {0x6c, 0x0a}, 350 | {0x6d, 0x55}, 351 | {0x6e, 0x11}, 352 | {0x6f, 0x9f}, 353 | {0xb0, 0x84}, 354 | { 0xff, 0xff } // END MARKER 355 | }; 356 | 357 | 358 | const struct regval_list qqqvga_yuv_ov7670[] PROGMEM = { 359 | 360 | {OV7670_REG_COM8, COM8_AEC|COM8_AWB }, 361 | // {OV7670_REG_COM8, COM8_FASTAEC|COM8_AECSTEP|COM8_AGC|COM8_AEC|COM8_AWB }, 362 | // {OV7670_REG_REG76, R76_BLKPCOR | R76_WHTPCOR }, 363 | // {OV7670_REG_COM13, COM13_UVSAT | COM13_GAMMA}, // enable auto UV saturation 364 | // {OV7670_REG_SATCTR, 0x60}, // set min satuation value 365 | 366 | // {OV7670_REG_CLKRC, CLKRC_4}, // 15fps (with 12MHz XCLK) 367 | // {OV7670_REG_DBLV, DBLV_X8}, // 15fps (with 12MHz XCLK) 368 | // {OV7670_REG_CLKRC, CLKRC_2}, // 30fps (with 12MHz XCLK) 369 | // {OV7670_REG_DBLV, DBLV_X4}, // 30fps (with 12MHz XCLK) 370 | {OV7670_REG_CLKRC, CLKRC_2}, // 30fps (with 12MHz XCLK) 371 | {OV7670_REG_DBLV, DBLV_X8}, // 30fps (with 12MHz XCLK) 372 | // {OV7670_REG_CLKRC, CLKRC_0}, // 45fps (with 12MHz XCLK) 373 | // {OV7670_REG_DBLV, DBLV_X6}, // 45fps (with 12MHz XCLK) 374 | 375 | // {OV7670_REG_COM7, 0x00}, // output format: yuv (is default) 376 | {OV7670_REG_COM15, 0x00}, // output range [10] to [F0] 377 | // {OV7670_REG_COM15, 0x80}, // output range [01] to [FE] 378 | // {OV7670_REG_COM15, 0xC0}, // output range [00] to [FF] (default) 379 | 380 | // full output window for 640x480 and proportional resolutions 381 | {OV7670_REG_HSTART, 0x16}, {OV7670_REG_HSTOP, 0x04}, {OV7670_REG_HREF, 0x24}, 382 | {OV7670_REG_VSTART, 0x02}, {OV7670_REG_VSTOP, 0x7a}, {OV7670_REG_VREF, 0x0a}, 383 | 384 | 385 | //------------ 386 | // edge enhancement regs: 387 | // 3F OV7670_REG_EDGE Edge Enhancement Adjustment Bit 388 | // [7:5]: Reserved, Bit 389 | // [4:0]: Edge enhancement factor 390 | // def 00 391 | //{OV7670_REG_EDGE, 0x0F}, 392 | //------------ 393 | // REG75 394 | // Bit[7:5]: Reserved 395 | // Bit[4:0]: Edge enhancement lower limit 396 | // {0x75, 0F} 397 | //------------ 398 | // Bit[7]: Black pixel correction: 0: Disable / 1: Enable 399 | // Bit[6]: White pixel correction: 0: Disable / 1: Enable 400 | // Bit[5]:Reserved 401 | // Bit[4:0]: Edge enhancement higher limit 402 | // {0x76, 01} REG76 403 | 404 | //test pattern 405 | // {0x70, 0x80}, 406 | // {0x71, 0x80}, 407 | // scale down to 80x60 408 | {OV7670_REG_COM14, COM14_DCWEN | COM14_PCLK_DIV_8 }, // divide by 8 409 | {OV7670_REG_SCALING_DCWCTR, SCALING_DCWCTR_8}, // downsample by 8 410 | {OV7670_REG_COM3, COM3_DCWEN}, // DCW enable, Scale enabled 411 | {OV7670_REG_SCALING_PCLK_DIV, SCALING_PCLK_DIV_8}, // divide by 8 412 | { 0xff, 0xff } // END MARKER 413 | 414 | }; 415 | 416 | 417 | const struct regval_list common_reglist_ov7670[] PROGMEM = {//from the linux driver 418 | 419 | { OV7670_REG_COM3, 0 }, { OV7670_REG_COM14, 0 }, 420 | /* Mystery scaling numbers */ 421 | { 0x70, 0x3a }, { 0x71, 0x35 }, 422 | { 0x72, 0x11 }, { 0x73, 0xf0 }, 423 | { 0xa2,/* 0x02 changed to 1*/1},{ OV7670_REG_COM10, 0x0 }, 424 | /* Gamma curve values */ 425 | { 0x7a, 0x20 }, { 0x7b, 0x10 }, 426 | { 0x7c, 0x1e }, { 0x7d, 0x35 }, 427 | { 0x7e, 0x5a }, { 0x7f, 0x69 }, 428 | { 0x80, 0x76 }, { 0x81, 0x80 }, 429 | { 0x82, 0x88 }, { 0x83, 0x8f }, 430 | { 0x84, 0x96 }, { 0x85, 0xa3 }, 431 | { 0x86, 0xaf }, { 0x87, 0xc4 }, 432 | { 0x88, 0xd7 }, { 0x89, 0xe8 }, 433 | /* AGC and AEC parameters. Note we start by disabling those features, 434 | then turn them only after tweaking the values. */ 435 | { OV7670_REG_COM8, COM8_FASTAEC | COM8_AECSTEP }, 436 | { OV7670_REG_GAIN, 0 }, { OV7670_REG_AECH, 0 }, 437 | { OV7670_REG_COM4, 0x40 }, /* magic reserved bit */ 438 | { OV7670_REG_COM9, 0x18 }, /* 4x gain + magic rsvd bit */ 439 | { OV7670_REG_BD50MAX, 0x05 }, { OV7670_REG_BD60MAX, 0x07 }, 440 | { OV7670_REG_AEW, 0x95 }, { OV7670_REG_AEB, 0x33 }, 441 | { OV7670_REG_VPT, 0xe3 }, { OV7670_REG_HAECC1, 0x78 }, 442 | { OV7670_REG_HAECC2, 0x68 }, { 0xa1, 0x03 }, /* magic */ 443 | { OV7670_REG_HAECC3, 0xd8 }, { OV7670_REG_HAECC4, 0xd8 }, 444 | { OV7670_REG_HAECC5, 0xf0 }, { OV7670_REG_HAECC6, 0x90 }, 445 | { OV7670_REG_HAECC7, 0x94 }, 446 | { OV7670_REG_COM8, COM8_FASTAEC|COM8_AECSTEP|COM8_AGC|COM8_AEC }, 447 | {0x30,0},{0x31,0},//disable some delays 448 | /* Almost all of these are magic "reserved" values. */ 449 | { OV7670_REG_COM5, 0x61 }, { OV7670_REG_COM6, 0x4b }, 450 | { 0x16, 0x02 }, { OV7670_REG_MVFP, 0x07 }, 451 | { 0x21, 0x02 }, { 0x22, 0x91 }, 452 | { 0x29, 0x07 }, { 0x33, 0x0b }, 453 | { 0x35, 0x0b }, { 0x37, 0x1d }, 454 | { 0x38, 0x71 }, { 0x39, 0x2a }, 455 | { OV7670_REG_COM12, 0x78 }, { 0x4d, 0x40 }, 456 | { 0x4e, 0x20 }, { OV7670_REG_GFIX, 0 }, 457 | /*{ 0x6b, 0x4a },*/ { 0x74,0x10}, 458 | { 0x8d, 0x4f }, { 0x8e, 0 }, 459 | { 0x8f, 0 }, { 0x90, 0 }, 460 | { 0x91, 0 }, { 0x96, 0 }, 461 | { 0x9a, 0 }, { 0xb0, 0x84 }, 462 | { 0xb1, 0x0c }, { 0xb2, 0x0e }, 463 | { 0xb3, 0x82 }, { 0xb8, 0x0a }, 464 | 465 | /* More reserved magic, some of which tweaks white balance */ 466 | { 0x43, 0x0a }, { 0x44, 0xf0 }, 467 | { 0x45, 0x34 }, { 0x46, 0x58 }, 468 | { 0x47, 0x28 }, { 0x48, 0x3a }, 469 | { 0x59, 0x88 }, { 0x5a, 0x88 }, 470 | { 0x5b, 0x44 }, { 0x5c, 0x67 }, 471 | { 0x5d, 0x49 }, { 0x5e, 0x0e }, 472 | { 0x6c, 0x0a }, { 0x6d, 0x55 }, 473 | { 0x6e, 0x11 }, { 0x6f, 0x9e }, /* it was 0x9F "9e for advance AWB" */ 474 | { 0x6a, 0x40 }, { OV7670_REG_BLUE, 0x40 }, 475 | { OV7670_REG_RED, 0x60 }, 476 | { OV7670_REG_COM8, COM8_FASTAEC|COM8_AECSTEP|COM8_AGC|COM8_AEC|COM8_AWB }, 477 | 478 | /* Matrix coefficients */ 479 | { 0x4f, 0x80 }, { 0x50, 0x80 }, 480 | { 0x51, 0 }, { 0x52, 0x22 }, 481 | { 0x53, 0x5e }, { 0x54, 0x80 }, 482 | { 0x58, 0x9e }, 483 | 484 | { OV7670_REG_COM16, COM16_AWBGAIN }, { OV7670_REG_EDGE, 0 }, 485 | { 0x75, 0x05 }, { OV7670_REG_REG76, 0xe1 }, 486 | { 0x4c, 0 }, { 0x77, 0x01 }, 487 | { OV7670_REG_COM13, /*0xc3*/0x48 }, { 0x4b, 0x09 }, 488 | { 0xc9, 0x60 }, /*{ OV7670_REG_COM16, 0x38 },*/ 489 | { 0x56, 0x40 }, 490 | 491 | { 0x34, 0x11 }, { OV7670_REG_COM11, COM11_EXP|COM11_HZAUTO }, 492 | { 0xa4, 0x82/*Wax 0x88*/ }, { 0x96, 0 }, 493 | { 0x97, 0x30 }, { 0x98, 0x20 }, 494 | { 0x99, 0x30 }, { 0x9a, 0x84 }, 495 | { 0x9b, 0x29 }, { 0x9c, 0x03 }, 496 | { 0x9d, 0x4c }, { 0x9e, 0x3f }, 497 | { 0x78, 0x04 }, 498 | 499 | /* Extra-weird stuff. Some sort of multiplexor register */ 500 | { 0x79, 0x01 }, { 0xc8, 0xf0 }, 501 | { 0x79, 0x0f }, { 0xc8, 0x00 }, 502 | { 0x79, 0x10 }, { 0xc8, 0x7e }, 503 | { 0x79, 0x0a }, { 0xc8, 0x80 }, 504 | { 0x79, 0x0b }, { 0xc8, 0x01 }, 505 | { 0x79, 0x0c }, { 0xc8, 0x0f }, 506 | { 0x79, 0x0d }, { 0xc8, 0x20 }, 507 | { 0x79, 0x09 }, { 0xc8, 0x80 }, 508 | { 0x79, 0x02 }, { 0xc8, 0xc0 }, 509 | { 0x79, 0x03 }, { 0xc8, 0x40 }, 510 | { 0x79, 0x05 }, { 0xc8, 0x30 }, 511 | { 0x79, 0x26 }, 512 | 513 | { 0xff, 0xff } // END MARKER 514 | }; 515 | 516 | 517 | #endif /* _OV7670_REGS_H */ 518 | 519 | 520 | -------------------------------------------------------------------------------- /arduvision_01/arduino/ov_fifo_test/ov772x_regs.h: -------------------------------------------------------------------------------- 1 | /* 2 | * A V4L2 driver for OmniVision ov7670 cameras. 3 | * 4 | * Copyright 2006 One Laptop Per Child Association, Inc. Written 5 | * by Jonathan Corbet with substantial inspiration from Mark 6 | * McClelland's ovcamchip code. 7 | * 8 | * Copyright 2006-7 Jonathan Corbet 9 | * 10 | * This file may be distributed under the terms of the GNU General 11 | * Public License, version 2. 12 | 13 | * Aug 18, 2014 - Adapted by David Sanz Kirbis: 14 | */ 15 | 16 | 17 | 18 | #ifndef _OV772x_REGS_H 19 | #define _OV772x_REGS_H 20 | 21 | 22 | #include 23 | #include 24 | #include "sensor.h" 25 | 26 | 27 | #define OV772x_RD_ADDR 0x42 28 | #define OV772x_WR_ADDR 0x43 29 | 30 | #define VGA_WIDTH 640 31 | #define VGA_HEIGHT 480 32 | #define QVGA_WIDTH 320 33 | #define QVGA_HEIGHT 240 34 | #define QQVGA_WIDTH 160 35 | #define QQVGA_HEIGHT 120 36 | #define QQQVGA_WIDTH 80 37 | #define QQQVGA_HEIGHT 60 38 | #define CIF_WIDTH 352 39 | #define CIF_HEIGHT 288 40 | #define QCIF_WIDTH 176 41 | #define QCIF_HEIGHT 144 42 | 43 | 44 | // register offset 45 | 46 | #define OV772x_REG_GAIN 0x00 // AGC - Gain control gain setting 47 | #define OV772x_REG_BLUE 0x01 // AWB - Blue channel gain setting 48 | #define OV772x_REG_RED 0x02 // AWB - Red channel gain setting 49 | #define OV772x_REG_GREEN 0x03 // AWB - Green channel gain setting 50 | #define OV772x_REG_COM1 0x04 // Common control 1 51 | #define OV772x_REG_BAVG 0x05 // U/B Average Level 52 | #define OV772x_REG_GAVG 0x06 // Y/Gb Average Level 53 | #define OV772x_REG_RAVG 0x07 // V/R Average Level 54 | #define OV772x_REG_AECH 0x08 // Exposure Value - AEC MSBs 55 | #define OV772x_REG_COM2 0x09 // Common control 2 56 | #define OV772x_REG_PID 0x0A // Product ID Number MSB 57 | #define OV772x_REG_VER 0x0B // Product ID Number LSB 58 | #define OV772x_REG_COM3 0x0C // Common control 3 59 | #define OV772x_REG_COM4 0x0D // Common control 4 60 | #define OV772x_REG_COM5 0x0E // Common control 5 61 | #define OV772x_REG_COM6 0x0F // Common control 6 62 | #define OV772x_REG_AEC 0x10 // Exposure Value 63 | #define OV772x_REG_CLKRC 0x11 // Internal clock 64 | #define OV772x_REG_COM7 0x12 // Common control 7 65 | #define OV772x_REG_COM8 0x13 // Common control 8 66 | #define OV772x_REG_COM9 0x14 // Common control 9 67 | #define OV772x_REG_COM10 0x15 // Common control 10 68 | #define OV772x_REG_REG16 0x16 // Register 16 69 | #define OV772x_REG_HSTART 0x17 // Horizontal sensor size 70 | #define OV772x_REG_HSIZE 0x18 // Horizontal frame (HREF column) end high 8-bit 71 | #define OV772x_REG_VSTART 0x19 // Vertical frame (row) start high 8-bit 72 | #define OV772x_REG_VSIZE 0x1A // Vertical sensor size 73 | #define OV772x_REG_PSHFT 0x1B // Data format - pixel delay select 74 | #define OV772x_REG_MIDH 0x1C // Manufacturer ID byte - high 75 | #define OV772x_REG_MIDL 0x1D // Manufacturer ID byte - low 76 | #define OV772x_REG_LAEC 0x1F // Fine AEC value 77 | #define OV772x_REG_COM11 0x20 // Common control 11 78 | #define OV772x_REG_BDBASE 0x22 // Banding filter Minimum AEC value 79 | #define OV772x_REG_DBSTEP 0x23 // Banding filter Maximum Setp 80 | #define OV772x_REG_AEW 0x24 // AGC/AEC - Stable operating region (upper limit) 81 | #define OV772x_REG_AEB 0x25 // AGC/AEC - Stable operating region (lower limit) 82 | #define OV772x_REG_VPT 0x26 // AGC/AEC Fast mode operating region 83 | #define OV772x_REG_REG28 0x28 // Register 28 84 | #define OV772x_REG_HOUTSIZE 0x29 // Horizontal data output size MSBs 85 | #define OV772x_REG_EXHCH 0x2A // Dummy pixel insert MSB 86 | #define OV772x_REG_EXHCL 0x2B // Dummy pixel insert LSB 87 | #define OV772x_REG_VOUTSIZE 0x2C // Vertical data output size MSBs 88 | #define OV772x_REG_ADVFL 0x2D // LSB of insert dummy lines in Vertical direction 89 | #define OV772x_REG_ADVFH 0x2E // MSG of insert dummy lines in Vertical direction 90 | #define OV772x_REG_YAVE 0x2F // Y/G Channel Average value 91 | #define OV772x_REG_LUMHTH 0x30 // Histogram AEC/AGC Luminance high level threshold 92 | #define OV772x_REG_LUMLTH 0x31 // Histogram AEC/AGC Luminance low level threshold 93 | #define OV772x_REG_HREF 0x32 // Image start and size control 94 | #define OV772x_REG_DM_LNL 0x33 // Dummy line low 8 bits 95 | #define OV772x_REG_DM_LNH 0x34 // Dummy line high 8 bits 96 | #define OV772x_REG_ADOFF_B 0x35 // AD offset compensation value for B channel 97 | #define OV772x_REG_ADOFF_R 0x36 // AD offset compensation value for R channel 98 | #define OV772x_REG_ADOFF_GB 0x37 // AD offset compensation value for Gb channel 99 | #define OV772x_REG_ADOFF_GR 0x38 // AD offset compensation value for Gr channel 100 | #define OV772x_REG_OFF_B 0x39 // Analog process B channel offset value 101 | #define OV772x_REG_OFF_R 0x3A // Analog process R channel offset value 102 | #define OV772x_REG_OFF_GB 0x3B // Analog process Gb channel offset value 103 | #define OV772x_REG_OFF_GR 0x3C // Analog process Gr channel offset value 104 | #define OV772x_REG_COM12 0x3D // Common control 12 105 | #define OV772x_REG_COM13 0x3E // Common control 13 106 | #define OV772x_REG_COM14 0x3F // Common control 14 107 | #define OV772x_REG_COM15 0x40 // Common control 15 108 | #define OV772x_REG_COM16 0x41 // Common control 16 109 | #define OV772x_REG_TGT_B 0x42 // BLC blue channel target value 110 | #define OV772x_REG_TGT_R 0x43 // BLC red channel target value 111 | #define OV772x_REG_TGT_GB 0x44 // BLC Gb channel target value 112 | #define OV772x_REG_TGT_GR 0x45 // BLC Gr channel target value 113 | // for ov7720 114 | #define OV772x_REG_LCC0 0x46 // Lens correction control 0 115 | #define OV772x_REG_LCC1 0x47 // Lens correction option 1 - X coordinate 116 | #define OV772x_REG_LCC2 0x48 // Lens correction option 2 - Y coordinate 117 | #define OV772x_REG_LCC3 0x49 // Lens correction option 3 118 | #define OV772x_REG_LCC4 0x4A // Lens correction option 4 - radius of the circular 119 | #define OV772x_REG_LCC5 0x4B // Lens correction option 5 120 | #define OV772x_REG_LCC6 0x4C // Lens correction option 6 121 | // for ov772x 122 | #define OV772x_REG_LC_CTR 0x46 // Lens correction control 123 | #define OV772x_REG_LC_XC 0x47 // X coordinate of lens correction center relative 124 | #define OV772x_REG_LC_YC 0x48 // Y coordinate of lens correction center relative 125 | #define OV772x_REG_LC_COEF 0x49 // Lens correction coefficient 126 | #define OV772x_REG_LC_RADI 0x4A // Lens correction radius 127 | #define OV772x_REG_LC_COEFB 0x4B // Lens B channel compensation coefficient 128 | #define OV772x_REG_LC_COEFR 0x4C // Lens R channel compensation coefficient 129 | 130 | #define OV772x_REG_FIXGAIN 0x4D // Analog fix gain amplifer 131 | #define OV772x_REG_AREF0 0x4E // Sensor reference control 132 | #define OV772x_REG_AREF1 0x4F // Sensor reference current control 133 | #define OV772x_REG_AREF2 0x50 // Analog reference control 134 | #define OV772x_REG_AREF3 0x51 // ADC reference control 135 | #define OV772x_REG_AREF4 0x52 // ADC reference control 136 | #define OV772x_REG_AREF5 0x53 // ADC reference control 137 | #define OV772x_REG_AREF6 0x54 // Analog reference control 138 | #define OV772x_REG_AREF7 0x55 // Analog reference control 139 | #define OV772x_REG_UFIX 0x60 // U channel fixed value output 140 | #define OV772x_REG_VFIX 0x61 // V channel fixed value output 141 | #define OV772x_REG_AWBB_BLK 0x62 // AWB option for advanced AWB 142 | #define OV772x_REG_AWB_CTRL0 0x63 // AWB control byte 0 143 | #define OV772x_REG_DSP_CTRL1 0x64 // DSP control byte 1 144 | #define OV772x_REG_DSP_CTRL2 0x65 // DSP control byte 2 145 | #define OV772x_REG_DSP_CTRL3 0x66 // DSP control byte 3 146 | #define OV772x_REG_DSP_CTRL4 0x67 // DSP control byte 4 147 | #define OV772x_REG_AWB_BIAS 0x68 // AWB BLC level clip 148 | #define OV772x_REG_AWB_CTRL1 0x69 // AWB control 1 149 | #define OV772x_REG_AWB_CTRL2 0x6A // AWB control 2 150 | #define OV772x_REG_AWB_CTRL3 0x6B // AWB control 3 151 | #define OV772x_REG_AWB_CTRL4 0x6C // AWB control 4 152 | #define OV772x_REG_AWB_CTRL5 0x6D // AWB control 5 153 | #define OV772x_REG_AWB_CTRL6 0x6E // AWB control 6 154 | #define OV772x_REG_AWB_CTRL7 0x6F // AWB control 7 155 | #define OV772x_REG_AWB_CTRL8 0x70 // AWB control 8 156 | #define OV772x_REG_AWB_CTRL9 0x71 // AWB control 9 157 | #define OV772x_REG_AWB_CTRL10 0x72 // AWB control 10 158 | #define OV772x_REG_AWB_CTRL11 0x73 // AWB control 11 159 | #define OV772x_REG_AWB_CTRL12 0x74 // AWB control 12 160 | #define OV772x_REG_AWB_CTRL13 0x75 // AWB control 13 161 | #define OV772x_REG_AWB_CTRL14 0x76 // AWB control 14 162 | #define OV772x_REG_AWB_CTRL15 0x77 // AWB control 15 163 | #define OV772x_REG_AWB_CTRL16 0x78 // AWB control 16 164 | #define OV772x_REG_AWB_CTRL17 0x79 // AWB control 17 165 | #define OV772x_REG_AWB_CTRL18 0x7A // AWB control 18 166 | #define OV772x_REG_AWB_CTRL19 0x7B // AWB control 19 167 | #define OV772x_REG_AWB_CTRL20 0x7C // AWB control 20 168 | #define OV772x_REG_AWB_CTRL21 0x7D // AWB control 21 169 | #define OV772x_REG_GAM1 0x7E // Gamma Curve 1st segment input end point 170 | #define OV772x_REG_GAM2 0x7F // Gamma Curve 2nd segment input end point 171 | #define OV772x_REG_GAM3 0x80 // Gamma Curve 3rd segment input end point 172 | #define OV772x_REG_GAM4 0x81 // Gamma Curve 4th segment input end point 173 | #define OV772x_REG_GAM5 0x82 // Gamma Curve 5th segment input end point 174 | #define OV772x_REG_GAM6 0x83 // Gamma Curve 6th segment input end point 175 | #define OV772x_REG_GAM7 0x84 // Gamma Curve 7th segment input end point 176 | #define OV772x_REG_GAM8 0x85 // Gamma Curve 8th segment input end point 177 | #define OV772x_REG_GAM9 0x86 // Gamma Curve 9th segment input end point 178 | #define OV772x_REG_GAM10 0x87 // Gamma Curve 10th segment input end point 179 | #define OV772x_REG_GAM11 0x88 // Gamma Curve 11th segment input end point 180 | #define OV772x_REG_GAM12 0x89 // Gamma Curve 12th segment input end point 181 | #define OV772x_REG_GAM13 0x8A // Gamma Curve 13th segment input end point 182 | #define OV772x_REG_GAM14 0x8B // Gamma Curve 14th segment input end point 183 | #define OV772x_REG_GAM15 0x8C // Gamma Curve 15th segment input end point 184 | #define OV772x_REG_SLOP 0x8D // Gamma curve highest segment slope 185 | #define OV772x_REG_DNSTH 0x8E // De-noise threshold 186 | #define OV772x_REG_EDGE_STRNGT 0x8F // Edge strength control when manual mode 187 | #define OV772x_REG_EDGE_TRSHLD 0x90 // Edge threshold control when manual mode 188 | #define OV772x_REG_DNSOFF 0x91 // Auto De-noise threshold control 189 | #define OV772x_REG_EDGE_UPPER 0x92 // Edge strength upper limit when Auto mode 190 | #define OV772x_REG_EDGE_LOWER 0x93 // Edge strength lower limit when Auto mode 191 | #define OV772x_REG_MTX1 0x94 // Matrix coefficient 1 192 | #define OV772x_REG_MTX2 0x95 // Matrix coefficient 2 193 | #define OV772x_REG_MTX3 0x96 // Matrix coefficient 3 194 | #define OV772x_REG_MTX4 0x97 // Matrix coefficient 4 195 | #define OV772x_REG_MTX5 0x98 // Matrix coefficient 5 196 | #define OV772x_REG_MTX6 0x99 // Matrix coefficient 6 197 | #define OV772x_REG_MTX_CTRL 0x9A // Matrix control 198 | #define OV772x_REG_BRIGHT 0x9B // Brightness control 199 | #define OV772x_REG_CNTRST 0x9C // Contrast contrast 200 | #define OV772x_REG_CNTRST_CTRL 0x9D // Contrast contrast center 201 | #define OV772x_REG_UVAD_J0 0x9E // Auto UV adjust contrast 0 202 | #define OV772x_REG_UVAD_J1 0x9F // Auto UV adjust contrast 1 203 | #define OV772x_REG_SCAL0 0xA0 // Scaling control 0 204 | #define OV772x_REG_SCAL1 0xA1 // Scaling control 1 205 | #define OV772x_REG_SCAL2 0xA2 // Scaling control 2 206 | #define OV772x_REG_FIFODLYM 0xA3 // FIFO manual mode delay control 207 | #define OV772x_REG_FIFODLYA 0xA4 // FIFO auto mode delay control 208 | #define OV772x_REG_SDE 0xA6 // Special digital effect control 209 | #define OV772x_REG_USAT 0xA7 // U component saturation control 210 | #define OV772x_REG_VSAT 0xA8 // V component saturation control 211 | // for ov7720 212 | #define OV772x_REG_HUE0 0xA9 // Hue control 0 213 | #define OV772x_REG_HUE1 0xAA // Hue control 1 214 | // for ov772x 215 | #define OV772x_REG_HUECOS 0xA9 // Cosine value 216 | #define OV772x_REG_HUESIN 0xAA // Sine value 217 | 218 | #define OV772x_REG_SIGN 0xAB // Sign bit for Hue and contrast 219 | #define OV772x_REG_DSPAUTO 0xAC // DSP auto function ON/OFF control 220 | 221 | // register detail 222 | 223 | 224 | // COM2 225 | #define OV772x_REG_SOFT_SLEEP_MODE 0x10 // Soft sleep mode 226 | // Output drive capability 227 | #define OV772x_REG_OCAP_1x 0x00 // 1x 228 | #define OV772x_REG_OCAP_2x 0x01 // 2x 229 | #define OV772x_REG_OCAP_3x 0x02 // 3x 230 | #define OV772x_REG_OCAP_4x 0x03 // 4x 231 | 232 | // COM3 233 | #define OV772x_REG_SWAP_MASK (SWAP_RGB | SWAP_YUV | SWAP_ML) 234 | #define OV772x_REG_IMG_MASK (VFLIP_IMG | HFLIP_IMG) 235 | 236 | #define OV772x_REG_VFLIP_IMG 0x80 // Vertical flip image ON/OFF selection 237 | #define OV772x_REG_HFLIP_IMG 0x40 // Horizontal mirror image ON/OFF selection 238 | #define OV772x_REG_SWAP_RGB 0x20 // Swap B/R output sequence in RGB mode 239 | #define OV772x_REG_SWAP_YUV 0x10 // Swap Y/UV output sequence in YUV mode 240 | #define OV772x_REG_SWAP_ML 0x08 // Swap output MSB/LSB 241 | // Tri-state option for output clock 242 | #define OV772x_REG_NOTRI_CLOCK 0x04 // 0: Tri-state at this period 243 | // 1: No tri-state at this period 244 | // Tri-state option for output data 245 | #define OV772x_REG_NOTRI_DATA 0x02 // 0: Tri-state at this period 246 | // 1: No tri-state at this period 247 | #define OV772x_REG_SCOLOR_TEST 0x01 // Sensor color bar test pattern 248 | 249 | // COM4 250 | // PLL frequency control 251 | #define OV772x_REG_PLL_BYPASS 0x00 // 00: Bypass PLL 252 | #define OV772x_REG_PLL_4x 0x40 // 01: PLL 4x 253 | #define OV772x_REG_PLL_6x 0x80 // 10: PLL 6x 254 | #define OV772x_REG_PLL_8x 0xc0 // 11: PLL 8x 255 | // AEC evaluate window 256 | #define OV772x_REG_AEC_FULL 0x00 // 00: Full window 257 | #define OV772x_REG_AEC_1p2 0x10 // 01: 1/2 window 258 | #define OV772x_REG_AEC_1p4 0x20 // 10: 1/4 window 259 | #define OV772x_REG_AEC_2p3 0x30 // 11: Low 2/3 window 260 | 261 | // COM5 262 | #define OV772x_REG_AFR_ON_OFF 0x80 // Auto frame rate control ON/OFF selection 263 | #define OV772x_REG_AFR_SPPED 0x40 // Auto frame rate control speed selection 264 | // Auto frame rate max rate control 265 | #define OV772x_REG_AFR_NO_RATE 0x00 // No reduction of frame rate 266 | #define OV772x_REG_AFR_1p2 0x10 // Max reduction to 1/2 frame rate 267 | #define OV772x_REG_AFR_1p4 0x20 // Max reduction to 1/4 frame rate 268 | #define OV772x_REG_AFR_1p8 0x30 // Max reduction to 1/8 frame rate 269 | // Auto frame rate active point control 270 | #define OV772x_REG_AF_2x 0x00 // Add frame when AGC reaches 2x gain 271 | #define OV772x_REG_AF_4x 0x04 // Add frame when AGC reaches 4x gain 272 | #define OV772x_REG_AF_8x 0x08 // Add frame when AGC reaches 8x gain 273 | #define OV772x_REG_AF_16x 0x0c // Add frame when AGC reaches 16x gain 274 | // AEC max step control 275 | #define OV772x_REG_AEC_NO_LIMIT 0x01 // 0 : AEC incease step has limit 276 | // 1 : No limit to AEC increase step 277 | 278 | // COM7 279 | // SCCB Register Reset 280 | #define OV772x_REG_SCCB_RESET 0x80 // 0 : No change 281 | // 1 : Resets all registers to default 282 | // Resolution selection 283 | #define OV772x_REG_SLCT_MASK 0x40 // Mask of VGA or QVGA 284 | #define OV772x_REG_SLCT_VGA 0x00 // 0 : VGA 285 | #define OV772x_REG_SLCT_QVGA 0x40 // 1 : QVGA 286 | #define OV772x_REG_ITU656_ON_OFF 0x20 // ITU656 protocol ON/OFF selection 287 | #define OV772x_REG_SENSOR_RAW 0x10 // Sensor RAW 288 | // RGB output format control 289 | #define OV772x_REG_FMT_MASK 0x0c // Mask of color format 290 | #define OV772x_REG_FMT_GBR422 0x00 // 00 : GBR 4:2:2 291 | #define OV772x_REG_FMT_RGB565 0x04 // 01 : RGB 565 292 | #define OV772x_REG_FMT_RGB555 0x08 // 10 : RGB 555 293 | #define OV772x_REG_FMT_RGB444 0x0c // 11 : RGB 444 294 | // Output format control 295 | #define OV772x_REG_OFMT_MASK 0x03 // Mask of output format 296 | #define OV772x_REG_OFMT_YUV 0x00 // 00 : YUV 297 | #define OV772x_REG_OFMT_P_BRAW 0x01 // 01 : Processed Bayer RAW 298 | #define OV772x_REG_OFMT_RGB 0x02 // 10 : RGB 299 | #define OV772x_REG_OFMT_BRAW 0x03 // 11 : Bayer RAW 300 | 301 | // COM8 302 | #define OV772x_REG_FAST_ALGO 0x80 // Enable fast AGC/AEC algorithm 303 | // AEC Setp size limit 304 | #define OV772x_REG_UNLMT_STEP 0x40 // 0 : Step size is limited 305 | // 1 : Unlimited step size 306 | #define OV772x_REG_BNDF_ON_OFF 0x20 // Banding filter ON/OFF 307 | #define OV772x_REG_AEC_BND 0x10 // Enable AEC below banding value 308 | #define OV772x_REG_AEC_ON_OFF 0x08 // Fine AEC ON/OFF control 309 | #define OV772x_REG_AGC_ON 0x04 // AGC Enable 310 | #define OV772x_REG_AWB_ON 0x02 // AWB Enable 311 | #define OV772x_REG_AEC_ON 0x01 // AEC Enable 312 | 313 | // COM9 314 | #define OV772x_REG_BASE_AECAGC 0x80 // Histogram or average based AEC/AGC 315 | // Automatic gain ceiling - maximum AGC value 316 | #define OV772x_REG_GAIN_2x 0x00 // 000 : 2x 317 | #define OV772x_REG_GAIN_4x 0x10 // 001 : 4x 318 | #define OV772x_REG_GAIN_8x 0x20 // 010 : 8x 319 | #define OV772x_REG_GAIN_16x 0x30 // 011 : 16x 320 | #define OV772x_REG_GAIN_32x 0x40 // 100 : 32x 321 | #define OV772x_REG_GAIN_64x 0x50 // 101 : 64x 322 | #define OV772x_REG_GAIN_128x 0x60 // 110 : 128x 323 | #define OV772x_REG_DROP_VSYNC 0x04 // Drop VSYNC output of corrupt frame 324 | #define OV772x_REG_DROP_HREF 0x02 // Drop HREF output of corrupt frame 325 | 326 | // COM11 327 | #define OV772x_REG_SGLF_ON_OFF 0x02 // Single frame ON/OFF selection 328 | #define OV772x_REG_SGLF_TRIG 0x01 // Single frame transfer trigger 329 | 330 | // HREF 331 | #define OV772x_REG_HREF_VSTART_SHIFT 6 // VSTART LSB 332 | #define OV772x_REG_HREF_HSTART_SHIFT 4 // HSTART 2 LSBs 333 | #define OV772x_REG_HREF_VSIZE_SHIFT 2 // VSIZE LSB 334 | #define OV772x_REG_HREF_HSIZE_SHIFT 0 // HSIZE 2 LSBs 335 | 336 | // EXHCH 337 | #define OV772x_REG_EXHCH_VSIZE_SHIFT 2 // VOUTSIZE LSB 338 | #define OV772x_REG_EXHCH_HSIZE_SHIFT 0 // HOUTSIZE 2 LSBs 339 | 340 | // DSP_CTRL1 341 | #define OV772x_REG_FIFO_ON 0x80 // FIFO enable/disable selection 342 | #define OV772x_REG_UV_ON_OFF 0x40 // UV adjust function ON/OFF selection 343 | #define OV772x_REG_YUV444_2_422 0x20 // YUV444 to 422 UV channel option selection 344 | #define OV772x_REG_CLR_MTRX_ON_OFF 0x10 // Color matrix ON/OFF selection 345 | #define OV772x_REG_INTPLT_ON_OFF 0x08 // Interpolation ON/OFF selection 346 | #define OV772x_REG_GMM_ON_OFF 0x04 // Gamma function ON/OFF selection 347 | #define OV772x_REG_AUTO_BLK_ON_OFF 0x02 // Black defect auto correction ON/OFF 348 | #define OV772x_REG_AUTO_WHT_ON_OFF 0x01 // White define auto correction ON/OFF 349 | 350 | // DSP_CTRL3 351 | #define OV772x_REG_UV_MASK 0x80 // UV output sequence option 352 | #define OV772x_REG_UV_ON 0x80 // ON 353 | #define OV772x_REG_UV_OFF 0x00 // OFF 354 | #define OV772x_REG_CBAR_MASK 0x20 // DSP Color bar mask 355 | #define OV772x_REG_CBAR_ON 0x20 // ON 356 | #define OV772x_REG_CBAR_OFF 0x00 // OFF 357 | 358 | // DSP_CTRL4 359 | #define OV772x_REG_DSP_OFMT_YUV 0x00 360 | #define OV772x_REG_DSP_OFMT_RGB 0x00 361 | #define OV772x_REG_DSP_OFMT_RAW8 0x02 362 | #define OV772x_REG_DSP_OFMT_RAW10 0x03 363 | 364 | // DSPAUTO (DSP Auto Function ON/OFF Control) 365 | #define OV772x_REG_AWB_ACTRL 0x80 // AWB auto threshold control 366 | #define OV772x_REG_DENOISE_ACTRL 0x40 // De-noise auto threshold control 367 | #define OV772x_REG_EDGE_ACTRL 0x20 // Edge enhancement auto strength control 368 | #define OV772x_REG_UV_ACTRL 0x10 // UV adjust auto slope control 369 | #define OV772x_REG_SCAL0_ACTRL 0x08 // Auto scaling factor control 370 | #define OV772x_REG_SCAL1_2_ACTRL 0x04 // Auto scaling factor control 371 | 372 | 373 | 374 | const struct regval_list qqvga_yuv_ov772x[] PROGMEM = { 375 | 376 | {OV772x_REG_COM7, OV772x_REG_SLCT_VGA}, // QVGA, YUY 377 | {OV772x_REG_COM12, 0x03}, // DC offset compensation for analog process 378 | {0x11, 0x01}, // 00/01/03/07 for 60/30/15/7.5fps - set to 30fps for QQVGA 379 | 380 | {OV772x_REG_DSP_CTRL2, 0x2f}, // DCW enable, zoom out enable 381 | 382 | // 160x120 383 | {0xA0, 0x0a}, // SCAL0, 1/4 vertical & horizontal down sampling 384 | {0xA1, 0x40}, // SCAL1, Horizontal Zoom Out Control, set ratio to 1/1 385 | {0xA2, 0x40}, // SCAL2, Vertical Zoom Out Control, set ratio to 1/1 386 | 387 | {OV772x_REG_HSTART, 0x23}, 388 | {OV772x_REG_HSIZE, 0xa0}, // Horizontal Sensor Size: full VGA (no windowing) 389 | {0x29, 0x28}, // Horizontal Data Output Size (160px) MSBs 390 | {OV772x_REG_VSTART, 0x07}, 391 | {OV772x_REG_VSIZE, 0xf0}, // Vertical Sensor Size: full VGA (no windowing) 392 | {0x2c, 0x3c}, // Vertical Data Output Size (120px)MSBs 393 | {OV772x_REG_HREF, 0x00}, 394 | {0x2a, 0x00}, // EXHCH 395 | {0x15,0x01}, // Output data range selection, Data from [10] to [F0] (8 MSBs) 396 | 397 | { 0xff, 0xff } // END MARKER 398 | 399 | }; 400 | 401 | const struct regval_list qqqvga_yuv_ov772x[] PROGMEM = { 402 | 403 | {OV772x_REG_COM7, OV772x_REG_SLCT_VGA}, // QVGA, YUY 404 | {OV772x_REG_COM12, 0x03}, // DC offset compensation for analog process 405 | {0x11, 0x01}, // 00/01/03/07 for 60/30/15/7.5fps - set to 30fps for QQVGA 406 | 407 | {OV772x_REG_DSP_CTRL2, 0x0f}, // 0x2f // DCW enable, zoom out enable 408 | 409 | {0xA0, 0x0f}, // SCAL0, 1/8 vertical & horizontal down sampling 410 | {0xA1, 0x80}, // SCAL1, Horizontal Zoom Out Control, set ratio to 1/2 411 | {0xA2, 0x80}, // SCAL2, Vertical Zoom Out Control, set ratio to 1/2 412 | 413 | {OV772x_REG_HSTART, 0x23}, 414 | {OV772x_REG_HSIZE, 0xa0}, // Horizontal Sensor Size: full VGA (no windowing) 415 | {0x29, 0x14}, // Horizontal Data Output Size (80px) MSBs 416 | {OV772x_REG_VSTART, 0x07}, 417 | {OV772x_REG_VSIZE, 0xf0}, // Vertical Sensor Size: full VGA (no windowing) 418 | {0x2c, 0x22}, // Vertical Data Output Size (60px)MSBs 419 | {OV772x_REG_HREF, 0x00}, 420 | {0x2a, 0x00}, // EXHCH 421 | 422 | {0x15,0x01}, // Output data range selection, Data from [10] to [F0] (8 MSBs) 423 | { 0xff, 0xff } // END MARKER 424 | 425 | }; 426 | 427 | 428 | const struct regval_list common_reglist_ov772x[] PROGMEM = 429 | { 430 | 431 | // most of these are color correction stuff 432 | {0x42, 0x7f}, 433 | {0x4d, 0x09}, 434 | {0x63, 0xe0}, // AWB_Ctrl0 435 | {OV772x_REG_COM3, 0x00}, // flip Y with UV 436 | {OV772x_REG_DSP_CTRL1, 0xff}, 437 | {OV772x_REG_DSP_CTRL3, 0x00}, // flip Y with UV 438 | {OV772x_REG_DSP_CTRL4, 0x48}, 439 | {0x13, 0xf0}, 440 | {0x0d, 0x61}, // 51/61/71 for different AEC/AGC window 441 | {0x0f, 0xc5}, 442 | {0x14, 0x11}, 443 | {0x22, 0x7f}, // ff/7f/3f/1f for 60/30/15/7.5fps 444 | {0x23, 0x03}, // 01/03/07/0f for 60/30/15/7.5fps 445 | {0x24, 0x40}, 446 | {0x25, 0x30}, 447 | {0x26, 0xa1}, 448 | {0x2b, 0x00}, // 00/9e for 60/50Hz 449 | {0x6b, 0xaa}, 450 | {0x13, 0xff}, 451 | {0x90, 0x05}, 452 | {0x91, 0x01}, 453 | {0x92, 0x03}, 454 | {0x93, 0x00}, 455 | {0x94, 0xb0}, 456 | {0x95, 0x9d}, 457 | {0x96, 0x13}, 458 | {0x97, 0x16}, 459 | {0x98, 0x7b}, 460 | {0x99, 0x91}, 461 | {0x9a, 0x1e}, 462 | {0x9e, 0x81}, 463 | //{0xa6, 0x03}, // Special Digital Effect Control; luma, contrast, saturation hue 464 | //{0x9b,0x00}, // set luma 465 | //{0x9c,0x25}, // set contrast 466 | //{0xa7,0x65}, // set saturation 467 | //{0xa8,0x65}, // set saturation 468 | //{0xa9,0x80}, // set hue 469 | //{0xaa,0x80}, // set hue 470 | {0x7e, 0x0c}, 471 | {0x7f, 0x16}, 472 | {0x80, 0x2a}, 473 | {0x81, 0x4e}, 474 | {0x82, 0x61}, 475 | {0x83, 0x6f}, 476 | {0x84, 0x7b}, 477 | {0x85, 0x86}, 478 | {0x86, 0x8e}, 479 | {0x87, 0x97}, 480 | {0x88, 0xa4}, 481 | {0x89, 0xaf}, 482 | {0x8a, 0xc5}, 483 | {0x8b, 0xd7}, 484 | {0x8c, 0xe8}, 485 | {0x8d, 0x20}, 486 | {0xff, 0xff} // END MARKER 487 | }; 488 | 489 | 490 | 491 | #endif /* _OV772x_REGS_H */ 492 | 493 | 494 | -------------------------------------------------------------------------------- /arduvision_01/arduino/ov_fifo_test/ov_fifo_test.ino: -------------------------------------------------------------------------------- 1 | /********************************************* 2 | * 3 | * Part of the ARDUVISION project 4 | * 5 | * by David Sanz Kirbis 6 | * 7 | * More info: http://www.arduvision.com 8 | * 9 | * 10 | * 2014 Aug 19 - Mixed some code to be used with an Atmega 328p 11 | * and the Arduino Wire library: 12 | * https://github.com/desaster/sensortest 13 | * http://forum.arduino.cc/index.php?topic=159557 14 | * 15 | * Aug 28 - Added definitions to be able to work with either 16 | * the hardware or the software serial. If using the 17 | * hardware UART, the TX and RX pins have to be 18 | * disconnected from the fifo or ensure they are not 19 | * written while reading the LS data bits. 20 | * - Included PinChangeInt library and change the code 21 | * so we dont wait while the CMOS IC loads the frame 22 | * into the fifo IC (which takes ~33ms at 30fps). 23 | * http://dl.bintray.com/greygnome/generic/pinchangeint-2.30beta.zip 24 | * Initial versions will just overwrite the start 25 | * of the fifo to store each new frame. 26 | * Sep 25 - Cleaned up and reorganized the code for a public release. 27 | * Increased baudrate after modifying arduino's HardwareSerial.cpp 28 | * see http://mekonik.wordpress.com/2009/03/02/modified-arduino-library-serial/ 29 | * 30 | ********************************************/ 31 | 32 | // -------------------------------- 33 | // http://subethasoftware.com/2013/04/09/arduino-compiler-problem-with-ifdefs-solved/ 34 | // BOF preprocessor bug prevent - insert me on top of your arduino-code 35 | // From: http://www.a-control.de/arduino-fehler/?lang=en 36 | #if 1 37 | __asm volatile ("nop"); 38 | #endif 39 | // -------------------------------- 40 | 41 | 42 | #include "IO_config.h" 43 | #include "sensor.h" 44 | #include "fifo.h" 45 | #include 46 | 47 | //#define USE_SOFT_SERIAL 48 | // serial stuff 49 | static const byte LF = 10; // line feed character 50 | #ifdef USE_SOFT_SERIAL 51 | #include 52 | static const unsigned int _BAUDRATE = 19200; // 19200 is the maximum reliable soft serial baud rate for 8MHz processors 53 | #define txPin A0 54 | #define rxPin A1 55 | SoftwareSerial mySerial = SoftwareSerial(rxPin, txPin); 56 | SoftwareSerial *serialPtr = &mySerial; 57 | #else 58 | // 38400 is the maximum supposed reliable UART baud rate for 8MHz processors 59 | // However, I've had succes at 500000bps with an USB-FTDI cable 60 | // I've modified the file arduino-1.5.6-r2/hardware/arduino/avr/cores/arduino/HardwareSerial.cpp 61 | // substituting all the lines with operations like this (for both rx and tx buffers): 62 | // 63 | // _rx_buffer_tail = (uint8_t)(_rx_buffer_tail + 1) % SERIAL_BUFFER_SIZE; 64 | // 65 | // for two lines like: 66 | // 67 | // _rx_buffer_tail++; 68 | // _rx_buffer_tail %= SERIAL_BUFFER_SIZE; 69 | // 70 | // see http://mekonik.wordpress.com/2009/03/02/modified-arduino-library-serial/ 71 | // 72 | static const unsigned long _BAUDRATE = 500000; 73 | HardwareSerial *serialPtr = &Serial; 74 | #endif 75 | 76 | uint8_t rcvbuf[16], rcvbufpos = 0, c; 77 | 78 | // fps calculation stuff 79 | static unsigned int oneSecond = 1000; 80 | unsigned int volatile frameCount = 0; 81 | unsigned int fps = 0; 82 | unsigned long volatile lastTime = 0; 83 | unsigned long volatile timeStamp = 0; 84 | 85 | //#define QQVGA 86 | #define QQQVGA 87 | 88 | #ifdef QQVGA 89 | static const uint8_t fW = 160; 90 | static const uint8_t fH = 120; 91 | static const frameFormat_t frameFormat = FF_QQVGA; 92 | #else ifdef QQQVGA 93 | static const uint8_t fW = 80; 94 | static const uint8_t fH = 60; 95 | static const frameFormat_t frameFormat = FF_QQQVGA; 96 | #endif 97 | 98 | static const uint8_t TRACK_BORDER = 4; // always multiple of 2 (YUYV: 2 pixels) 99 | static const uint8_t YUYV_BPP = 2; // bytes per pixel 100 | static const unsigned int MAX_FRAME_LEN = fW * YUYV_BPP; 101 | byte rowBuf[MAX_FRAME_LEN]; 102 | unsigned int volatile nRowsSent = 0; 103 | boolean volatile bRequestPending = false; 104 | boolean volatile bNewFrame = false; 105 | uint8_t volatile thresh = 128; 106 | 107 | enum serialRequest_t { 108 | SEND_NONE = 0, 109 | SEND_DARK, 110 | SEND_BRIG, 111 | SEND_FPS, 112 | SEND_0PPB = MAX_FRAME_LEN, 113 | SEND_1PPB = fW, 114 | SEND_2PPB = fW/2, 115 | SEND_4PPB = fW/4, 116 | SEND_8PPB =fW/8 117 | }; 118 | 119 | serialRequest_t serialRequest = SEND_NONE; 120 | 121 | 122 | // ***************************************************** 123 | // SETUP 124 | // ***************************************************** 125 | void setup() 126 | { 127 | setup_IO_ports(); 128 | 129 | serialPtr->begin(_BAUDRATE); 130 | 131 | serialPtr->println("Initializing sensor..."); 132 | for (int i = 0; i < 10; i ++) { 133 | unsigned int result = sensor_init(frameFormat); 134 | if (result != 0) { 135 | serialPtr->print("inited OK, sensor PID: "); 136 | serialPtr->println(result, HEX); 137 | break; 138 | } 139 | else if (i == 5) { 140 | serialPtr->println("PANIC! sensor init keeps failing!"); 141 | while (1); 142 | } else { 143 | serialPtr->println("retrying..."); 144 | delay(300); 145 | } 146 | } 147 | attachInterrupt(VSYNC_INT, &vsyncIntFunc, FALLING); 148 | delay(100); 149 | } 150 | // ***************************************************** 151 | // LOOP 152 | // ***************************************************** 153 | void loop() 154 | { 155 | 156 | 157 | } 158 | 159 | // ***************************************************** 160 | // VSYNC INTERRUPT HANDLER 161 | // ***************************************************** 162 | void __inline__ vsyncIntFunc() { 163 | DISABLE_WREN; // disable writing to fifo 164 | 165 | if (bRequestPending && bNewFrame) { 166 | detachInterrupt(VSYNC_INT); 167 | processRequest(); 168 | bRequestPending = false; 169 | bNewFrame = false; 170 | attachInterrupt(VSYNC_INT, &vsyncIntFunc, FALLING); 171 | } 172 | else { 173 | ENABLE_WRST; 174 | //__delay_cycles(500); 175 | SET_RCLK_H; 176 | //__delay_cycles(100); 177 | SET_RCLK_L; 178 | DISABLE_WRST; 179 | _delay_cycles(10); 180 | 181 | ENABLE_WREN; // enable writing to fifo 182 | bNewFrame = true; 183 | } 184 | } 185 | 186 | // ************************************************************** 187 | // PROCESS SERIAL REQUEST 188 | // ************************************************************** 189 | void processRequest() { 190 | 191 | fifo_rrst(); 192 | 193 | switch (serialRequest) { 194 | case SEND_0PPB: for (int i =0; i< fH; i++) { 195 | fifo_readRow0ppb(rowBuf, rowBuf+serialRequest); 196 | serialPtr->write(rowBuf, serialRequest); 197 | serialPtr->write(LF); 198 | } break; 199 | case SEND_1PPB: for (int i =0; i< fH; i++) { 200 | fifo_readRow1ppb(rowBuf, rowBuf+serialRequest); 201 | serialPtr->write(rowBuf, serialRequest); 202 | serialPtr->write(LF); 203 | } break; 204 | case SEND_2PPB: for (int i =0; i< fH; i++) { 205 | fifo_readRow2ppb(rowBuf, rowBuf+serialRequest); 206 | serialPtr->write(rowBuf, serialRequest); 207 | serialPtr->write(LF); 208 | } break; 209 | case SEND_4PPB: for (int i =0; i< fH; i++) { 210 | fifo_readRow4ppb(rowBuf, rowBuf+serialRequest); 211 | serialPtr->write(rowBuf, serialRequest); 212 | serialPtr->write(LF); 213 | } break; 214 | case SEND_8PPB: for (int i =0; i< fH; i++) { 215 | fifo_readRow8ppb(rowBuf, rowBuf+serialRequest, thresh); 216 | serialPtr->write(rowBuf, serialRequest); 217 | serialPtr->write(LF); 218 | } break; 219 | case SEND_BRIG: fifo_getBrig(rowBuf, fW, fH, TRACK_BORDER, thresh); 220 | serialPtr->write(rowBuf, 4); 221 | serialPtr->write(LF); 222 | break; 223 | case SEND_DARK: fifo_getDark(rowBuf, fW, fH, TRACK_BORDER, thresh); 224 | serialPtr->write(rowBuf, 4); 225 | serialPtr->write(LF); 226 | break; 227 | case SEND_FPS: calcFPS(fps); 228 | serialPtr->print(fps, DEC); 229 | serialPtr->write(LF); 230 | break; 231 | 232 | default : break; 233 | } 234 | } 235 | 236 | 237 | // ************************************************************** 238 | // CALCULATE FPS 239 | // ************************************************************** 240 | void calcFPS(unsigned int ¤tFPS) { 241 | unsigned long currTime = millis(); 242 | unsigned long currTimeDiff = currTime-lastTime; 243 | if (currTimeDiff >= oneSecond) { 244 | lastTime = currTime; 245 | currentFPS = (oneSecond*frameCount)/currTimeDiff; 246 | frameCount = 0; 247 | 248 | } 249 | while (GET_VSYNC); // wait for an old frame to end 250 | while (!GET_VSYNC);// wait for a new frame to start 251 | frameCount++; 252 | } 253 | // ************************************************************** 254 | // SERIAL EVENT 255 | // ************************************************************** 256 | 257 | void serialEvent() { 258 | while (serialPtr->available()) { 259 | // get the new byte: 260 | c = serialPtr->read(); 261 | if (c != LF) { 262 | rcvbuf[rcvbufpos++] = c; 263 | } else if (c == LF) { 264 | rcvbuf[rcvbufpos++] = 0; 265 | rcvbufpos = 0; 266 | parseSerialBuffer(); 267 | } 268 | } 269 | } 270 | 271 | // ***************************************************** 272 | // PARSE SERIAL BUFFER 273 | // **************************************************** 274 | void parseSerialBuffer(void) { 275 | if (strcmp((char *) rcvbuf, "hello") == 0) { 276 | serialPtr->print("Hello to you too!\n"); 277 | } else if ( strlen((char *) rcvbuf) > 5 && 278 | strncmp((char *) rcvbuf, "send ", 5) == 0) { 279 | serialRequest = (serialRequest_t)atoi((char *) (rcvbuf + 5)); 280 | serialPtr->print("ACK\n"); 281 | bRequestPending = true; 282 | } 283 | else if (strlen((char *) rcvbuf) > 5 && 284 | strncmp((char *) rcvbuf, "dark ", 5) == 0) { 285 | thresh = atoi((char *) (rcvbuf + 5)); 286 | serialPtr->print("ACK\n"); 287 | serialRequest = SEND_DARK; 288 | bRequestPending = true; 289 | } 290 | else if (strlen((char *) rcvbuf) > 5 && 291 | strncmp((char *) rcvbuf, "brig ", 5) == 0) { 292 | thresh = atoi((char *) (rcvbuf + 5)); 293 | serialPtr->print("ACK\n"); 294 | serialRequest = SEND_BRIG; 295 | bRequestPending = true; 296 | } 297 | else if (strlen((char *) rcvbuf) > 7 && 298 | strncmp((char *) rcvbuf, "thresh ", 7) == 0) { 299 | thresh = atoi((char *) (rcvbuf + 7)); 300 | } 301 | } 302 | 303 | -------------------------------------------------------------------------------- /arduvision_01/arduino/ov_fifo_test/sensor.cpp: -------------------------------------------------------------------------------- 1 | 2 | //************************** 3 | 4 | 5 | //************************** 6 | 7 | 8 | #include "sensor.h" 9 | #include "ov772x_regs.h" 10 | #include "ov7670_regs.h" 11 | 12 | 13 | #include 14 | #include 15 | 16 | #include "delay.h" 17 | 18 | uint16_t sensor_init(frameFormat_t fFormat) 19 | { 20 | regval_list *format_reglist, *common_reglist; 21 | uint8_t resetReg, resetCommand; 22 | 23 | Wire.begin(); 24 | 25 | _delayMilliseconds(5); 26 | 27 | uint16_t productID = sensor_readReg(REG_PID); 28 | switch(productID) { 29 | case 0x76: //ov7670 30 | productID <<= 8; 31 | productID |= sensor_readReg(REG_VER); 32 | switch (fFormat) { 33 | default: 34 | case FF_QQVGA: format_reglist = (regval_list*)qqvga_yuv_ov7670; break; 35 | case FF_QQQVGA: format_reglist = (regval_list*)qqqvga_yuv_ov7670; break; 36 | } 37 | common_reglist = (regval_list*)common_reglist_ov7670; 38 | resetReg = 0x12; 39 | resetCommand = 0x80; 40 | break; 41 | case 0x77: //ov772x 42 | productID <<= 8; 43 | productID |= sensor_readReg(REG_VER); 44 | switch (fFormat) { 45 | default: 46 | case FF_QQVGA: format_reglist = (regval_list*)qqvga_yuv_ov772x; break; 47 | case FF_QQQVGA: format_reglist = (regval_list*)qqqvga_yuv_ov772x; break; 48 | } 49 | common_reglist = (regval_list*)common_reglist_ov772x; 50 | resetReg = 0x12; 51 | resetCommand = 0x80; 52 | break; 53 | default: return 0; 54 | break; 55 | } 56 | 57 | sensor_writeReg(resetReg, resetCommand); // reset to default values 58 | delay(300); // Setting time for register change 59 | sensor_writeRegs(common_reglist); 60 | delay(300); // Setting time for register change 61 | sensor_writeRegs(format_reglist); 62 | delay(300); // Setting time for register change 63 | return productID; 64 | } 65 | //************************** 66 | // Write byte value regDat to the camera register addressed by regID 67 | uint8_t sensor_writeReg(uint8_t regID, uint8_t regDat) { 68 | Wire.beginTransmission(OV772x_WR_ADDR >> 1); 69 | Wire.write(regID & 0x00FF); 70 | Wire.write(regDat & 0x00FF); 71 | uint8_t result = Wire.endTransmission(); 72 | //delay(1); 73 | return result; 74 | } 75 | //************************** 76 | void sensor_writeRegs(const regval_list reglist[]) { 77 | uint8_t reg_addr; 78 | uint8_t reg_val; 79 | const struct regval_list *next = reglist; 80 | while ((reg_addr != 0xFF) | (reg_val != 0xFF)){ 81 | reg_addr = pgm_read_byte(&next->reg_num); 82 | reg_val = pgm_read_byte(&next->value); 83 | sensor_writeReg(reg_addr, reg_val); 84 | next++; 85 | } 86 | } 87 | //************************** 88 | // Read a byte value from the camera addressed at regID, and store it at 89 | // memory location pointed to by regDat. Return 1 on success, 0 on failure. 90 | uint8_t sensor_readReg(uint8_t regID) { 91 | uint8_t regDat; 92 | Wire.beginTransmission(OV772x_RD_ADDR >> 1); 93 | Wire.write(regID & 0x00FF); 94 | Wire.endTransmission(); 95 | Wire.requestFrom((OV772x_RD_ADDR >> 1),1); 96 | if(Wire.available()) { 97 | regDat = Wire.read(); 98 | //delay(1); 99 | return regDat; 100 | } else { 101 | return 0; 102 | } 103 | } 104 | 105 | //************************** 106 | void sensor_printlnRegs(const regval_list reglist[], Stream &destPort) { 107 | uint8_t reg_addr; 108 | uint8_t reg_val; 109 | uint8_t regRead_val; 110 | 111 | const struct regval_list *next = reglist; 112 | while ((reg_addr != 0xFF) | (reg_val != 0xFF)){ 113 | reg_addr = pgm_read_byte(&next->reg_num); 114 | reg_val = pgm_read_byte(&next->value); 115 | regRead_val = sensor_readReg(reg_addr); 116 | next++; 117 | destPort.print("{"); 118 | destPort.print(reg_addr, HEX); 119 | destPort.print(", "); 120 | destPort.print(regRead_val, HEX); 121 | destPort.println("},"); 122 | 123 | } 124 | } 125 | 126 | 127 | 128 | -------------------------------------------------------------------------------- /arduvision_01/arduino/ov_fifo_test/sensor.h: -------------------------------------------------------------------------------- 1 | #ifndef _SENSOR_H 2 | #define _SENSOR_H 3 | 4 | 5 | #include 6 | 7 | 8 | #include "delay.h" 9 | #define REG_PID 0x0a // Product ID MSB 10 | #define REG_VER 0x0b // Product ID LSB 11 | 12 | struct regval_list { 13 | uint8_t reg_num; 14 | uint8_t value; 15 | }; 16 | enum frameFormat_t { 17 | FF_QQVGA, 18 | FF_QQQVGA 19 | }; 20 | 21 | 22 | uint16_t sensor_init(frameFormat_t fFormat); 23 | void al422_loadFrame(void); 24 | uint8_t sensor_writeReg(uint8_t regID, uint8_t regDat); 25 | void sensor_writeRegs(const regval_list reglist[]); 26 | uint8_t sensor_readReg(uint8_t regID); 27 | void sensor_printlnRegs(const regval_list reglist[]); 28 | void wait(void); 29 | 30 | #endif /* _SENSOR_H */ 31 | -------------------------------------------------------------------------------- /arduvision_01/docs/arduino_ov_fifo_connections.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/dasaki/arduvision/950bd8788613f60f09086abd510b397fe3b9d73e/arduvision_01/docs/arduino_ov_fifo_connections.png -------------------------------------------------------------------------------- /arduvision_01/processing/receive_stream/globalDefinitions.java: -------------------------------------------------------------------------------- 1 | 2 | final class G_DEF { 3 | public final static int BAUDRATE = 500000; 4 | 5 | public final static char LF = '\n'; // Linefeed in ASCII 6 | public final static char CR = '\r'; // Carriage return in ASCII 7 | 8 | public final static int SCR_W = 640; 9 | public final static int SCR_H = 480; 10 | public final static int F_W = 80; 11 | public final static int F_H = 60; 12 | public final static int BPP = 2; 13 | public final static int FONT_SIZE = 18; 14 | public final static int FONT_BKG_SIZE = (int)(FONT_SIZE*(float)1.5); 15 | public final static float DRAW_SCALE = (float)SCR_W / (float)F_W; 16 | 17 | public final static int MAX_ROW_LEN = F_W*BPP; // pixels + LF character 18 | public final static int MAX_ROW_BUFF_LEN = MAX_ROW_LEN+1; // pixels + LF character 19 | public final static int ACK_BUF_LEN = 255; // serial buffer to store "ACK"+LF 20 | public final static long SERIAL_TIMEOUT = 50; // milliseconds to wait for ACK 21 | } 22 | 23 | enum requestStatus_t { 24 | IDLE, REQUESTED, TIMEOUT, ARRIVING, RECEIVED, PROCESSING 25 | }; 26 | 27 | enum request_t { 28 | NONE(0), 29 | TRACKDARK(1), 30 | TRACKBRIG(2), 31 | STREAM8PPB(G_DEF.F_W/8), 32 | STREAM4PPB(G_DEF.F_W/4), 33 | STREAM2PPB(G_DEF.F_W/2), 34 | STREAM1PPB(G_DEF.F_W), 35 | STREAM0PPB(G_DEF.F_W*G_DEF.BPP); 36 | 37 | private int value; 38 | 39 | private request_t(int value) { 40 | this.value = value; 41 | } 42 | 43 | public int getParam() { 44 | return value; 45 | } 46 | }; 47 | 48 | -------------------------------------------------------------------------------- /arduvision_01/processing/receive_stream/receive_stream.pde: -------------------------------------------------------------------------------- 1 | /************************************************************** 2 | * 3 | * Part of the ARDUVISION project 4 | * 5 | * by David Sanz Kirbis 6 | * 7 | * Receive the image and/or tracking data from a CMOS sensor 8 | * controlled by an Arduino board. 9 | * In the arduino side use the example sketch "ov_fifo_test.ino" 10 | * 11 | * More info: http://www.arduvision.com 12 | * 13 | * 14 | * 15 | **************************************************************/ 16 | 17 | 18 | import processing.serial.*; 19 | import java.util.*; 20 | 21 | 22 | 23 | Serial serialPort; 24 | 25 | request_t request; 26 | requestStatus_t reqStatus = requestStatus_t.IDLE; 27 | 28 | // incoming serial 29 | byte[] ackBuff = new byte[G_DEF.ACK_BUF_LEN]; 30 | byte[][] pix = new byte[G_DEF.F_H][G_DEF.MAX_ROW_LEN]; 31 | 32 | double waitTimeout = 0; 33 | double fpsTimeStamp = 0; 34 | 35 | PFont myFont; 36 | PImage currFrame; 37 | 38 | boolean bSerialDebug = true; 39 | 40 | int currRow = 0; 41 | byte thresh = (byte)130; 42 | 43 | PVector lastCenter = new PVector(0,0); 44 | float tmp_x0 = 0, tmp_y0 = 0, tmp_x1 = 0, tmp_y1 = 0; 45 | float x0 = 0, y0 = 0, x1 = 0, y1 = 0; 46 | 47 | boolean bKalmanEnabled = true; 48 | simpleKalman filter_x0 = new simpleKalman(); 49 | simpleKalman filter_y0 = new simpleKalman(); 50 | simpleKalman filter_x1 = new simpleKalman(); 51 | simpleKalman filter_y1 = new simpleKalman(); 52 | 53 | // ************************************************************ 54 | // SETUP 55 | // ************************************************************ 56 | 57 | void setup() { 58 | size(640, 507); 59 | frameRate(99); 60 | noSmooth(); 61 | currFrame = createImage(G_DEF.F_W, G_DEF.F_H, RGB); 62 | 63 | 64 | // create a font with the third font available to the system: 65 | myFont = createFont("Arial", G_DEF.FONT_SIZE); 66 | textFont(myFont); 67 | 68 | // List all the available serial serialPorts: 69 | printArray(Serial.list()); 70 | 71 | delay(500); 72 | serialPort = new Serial(this, "/dev/ttyUSB0", G_DEF.BAUDRATE); 73 | serialPort.bufferUntil(G_DEF.LF); 74 | serialPort.clear(); 75 | delay(2000); 76 | reqStatus = reqStatus.IDLE; 77 | request = request.NONE; 78 | } 79 | 80 | // ************************************************************ 81 | // DRAW 82 | // ************************************************************ 83 | void draw() { 84 | switch (request) { 85 | case NONE: reqStatus = requestStatus_t.IDLE; 86 | background(0); 87 | drawInfo(); 88 | break; 89 | case TRACKDARK: 90 | case TRACKBRIG: switch (reqStatus) { 91 | case RECEIVED: drawTracking(); 92 | drawFPS(); 93 | reqStatus = requestStatus_t.IDLE; 94 | break; 95 | case TIMEOUT: 96 | case IDLE: reqTracking(request); 97 | reqStatus = requestStatus_t.REQUESTED; 98 | waitTimeout = G_DEF.SERIAL_TIMEOUT + millis(); 99 | break; 100 | case REQUESTED: if (millis() > waitTimeout) reqStatus = requestStatus_t.TIMEOUT; 101 | break; 102 | case ARRIVING: break; 103 | default : break; 104 | } 105 | drawInfo(); 106 | break; 107 | case STREAM0PPB: 108 | case STREAM1PPB: 109 | case STREAM2PPB: 110 | case STREAM4PPB: 111 | case STREAM8PPB: switch (reqStatus) { 112 | case RECEIVED: reqStatus = requestStatus_t.PROCESSING; 113 | buff2pixFrame(pix, currFrame, request); 114 | image(currFrame,0,0, G_DEF.F_W*G_DEF.DRAW_SCALE,G_DEF.F_H*G_DEF.DRAW_SCALE); 115 | drawFPS(); 116 | reqStatus = requestStatus_t.IDLE; 117 | break; 118 | case TIMEOUT: 119 | case IDLE: reqImage(request); 120 | reqStatus = requestStatus_t.REQUESTED; 121 | waitTimeout = G_DEF.SERIAL_TIMEOUT + millis(); 122 | break; 123 | case REQUESTED: if (millis() > waitTimeout) reqStatus = requestStatus_t.TIMEOUT; 124 | break; 125 | case ARRIVING: break; 126 | case PROCESSING: break; 127 | default : break; 128 | } 129 | drawInfo(); 130 | break; 131 | default : break; 132 | } 133 | } 134 | 135 | // ************************************************************ 136 | // SERIAL EVENT HANDLER 137 | // ************************************************************ 138 | void serialEvent(Serial serialPort) { 139 | 140 | if (reqStatus == requestStatus_t.REQUESTED) { 141 | int numBytesRead = serialPort.readBytesUntil(G_DEF.LF, ackBuff); 142 | if ((numBytesRead >= 4) && 143 | (ackBuff[numBytesRead-4] == 'A') && 144 | (ackBuff[numBytesRead-3] == 'C') && 145 | (ackBuff[numBytesRead-2] == 'K') ) { 146 | reqStatus = requestStatus_t.ARRIVING; 147 | } else if (millis() > waitTimeout) { 148 | reqStatus = requestStatus_t.TIMEOUT; 149 | } 150 | } 151 | else if (reqStatus == requestStatus_t.ARRIVING) { 152 | parseSerialData(); 153 | } 154 | else { 155 | if (bSerialDebug) print(serialPort.readStringUntil(G_DEF.LF)); 156 | } 157 | } 158 | 159 | // ************************************************************ 160 | // PARSE SERIAL DATA 161 | // ************************************************************ 162 | void parseSerialData() { 163 | switch (request) { 164 | case NONE: break; 165 | case TRACKDARK: 166 | case TRACKBRIG: tmp_x0 = int(serialPort.read()); 167 | tmp_y0 = int(serialPort.read()); 168 | tmp_x1 = int(serialPort.read()); 169 | tmp_y1 = int(serialPort.read()); 170 | reqStatus = requestStatus_t.RECEIVED; 171 | break; 172 | case STREAM0PPB: 173 | case STREAM1PPB: 174 | case STREAM2PPB: 175 | case STREAM4PPB: 176 | case STREAM8PPB: serialPort.readBytes(pix[currRow]); 177 | serialPort.clear(); 178 | currRow++; 179 | if (currRow >= G_DEF.F_H) { 180 | reqStatus = requestStatus_t.RECEIVED; // frame ready on buffer 181 | currRow = 0; 182 | if (bSerialDebug) println(); 183 | } 184 | break; 185 | default : break; 186 | } 187 | 188 | } 189 | 190 | // ************************************************************ 191 | // REQUEST IMAGE 192 | // ************************************************************ 193 | void reqImage(request_t req) { 194 | currRow = 0; 195 | serialPort.clear(); 196 | serialPort.write("thresh "+Integer.toString(int(thresh))+G_DEF.LF); 197 | serialPort.write("send "+Integer.toString(req.getParam())+G_DEF.LF); 198 | } 199 | 200 | // ************************************************************ 201 | // REQUEST TRACKING DATA 202 | // ************************************************************ 203 | void reqTracking(request_t req) { 204 | 205 | serialPort.clear(); 206 | if (req == request_t.TRACKDARK) 207 | serialPort.write("dark "+Integer.toString(int(thresh))+G_DEF.LF); 208 | else if (req == request_t.TRACKBRIG) 209 | serialPort.write("brig "+Integer.toString(int(thresh))+G_DEF.LF); 210 | 211 | } 212 | 213 | // ************************************************************ 214 | // DRAW SCREEN INFO 215 | // ************************************************************ 216 | void drawInfo() { 217 | String modeStr = "Press space to toggle MODE: "+request; 218 | pushStyle(); 219 | pushMatrix(); 220 | noStroke(); 221 | fill(64); 222 | rect(0, height-G_DEF.FONT_BKG_SIZE, width, G_DEF.FONT_BKG_SIZE); 223 | fill(255); 224 | textAlign(LEFT, TOP); 225 | text(modeStr, 20, height-G_DEF.FONT_BKG_SIZE); 226 | textAlign(RIGHT, TOP); 227 | text("thresh (+/-): "+int(thresh), width-20, height-G_DEF.FONT_BKG_SIZE); 228 | popMatrix(); 229 | popStyle(); 230 | } 231 | 232 | // ************************************************************ 233 | // DRAW FPS 234 | // ************************************************************ 235 | void drawFPS() { 236 | long currTime = millis(); 237 | float fps =1000.0/(float)(currTime-fpsTimeStamp); 238 | 239 | pushStyle(); 240 | pushMatrix(); 241 | noStroke(); 242 | fill(0); 243 | rect(20, 20, textWidth("FPS: "+fps), G_DEF.FONT_SIZE); 244 | fill(255); 245 | translate(0,-2); 246 | textAlign(LEFT, TOP); 247 | text("FPS: "+fps, 20, 20); 248 | popMatrix(); 249 | popStyle(); 250 | fpsTimeStamp = currTime; 251 | } 252 | 253 | // ************************************************************ 254 | // DRAW TRACKING 255 | // ************************************************************ 256 | void drawTracking() { 257 | pushStyle(); 258 | noFill(); 259 | strokeWeight(3); 260 | 261 | if (tmp_x1-tmp_x0 > 3 && tmp_x1-tmp_x0 < G_DEF.F_W/2 && tmp_y1-tmp_y0 < G_DEF.F_H/2 && tmp_y1-tmp_y0 > 3) { 262 | stroke(0); 263 | float minX = width-x0*G_DEF.DRAW_SCALE; 264 | float minY = y0*G_DEF.DRAW_SCALE; 265 | float wX = -(x1-x0)*G_DEF.DRAW_SCALE; 266 | float hY = (y1-y0)*G_DEF.DRAW_SCALE; 267 | float centX = minX+wX/2; 268 | float centY = minY+hY/2; 269 | rect(minX, minY, wX, hY ); 270 | line( centX-10, centY, centX+10, centY ); 271 | line( centX, centY-10, centX, centY+10 ); 272 | if (bKalmanEnabled) { 273 | x0 = (float)filter_x0.update(tmp_x0); 274 | y0 = (float)filter_y0.update(tmp_y0); 275 | x1 = (float)filter_x1.update(tmp_x1); 276 | y1 = (float)filter_y1.update(tmp_y1); 277 | } 278 | else { 279 | x0 = tmp_x0; 280 | y0 = tmp_y0; 281 | x1 = tmp_x1; 282 | y1 = tmp_y1; 283 | } 284 | stroke(255,0,0); 285 | minX = width-x0*G_DEF.DRAW_SCALE; 286 | minY = y0*G_DEF.DRAW_SCALE; 287 | wX = -(x1-x0)*G_DEF.DRAW_SCALE; 288 | hY = (y1-y0)*G_DEF.DRAW_SCALE; 289 | centX = minX+wX/2; 290 | centY = minY+hY/2; 291 | 292 | rect(minX, minY, wX, hY ); 293 | 294 | 295 | line( centX-10, centY, centX+10, centY ); 296 | line( centX, centY-10, centX, centY+10 ); 297 | stroke(0,0,255); 298 | line(lastCenter.x, lastCenter.y,centX, centY); 299 | lastCenter.x = centX; 300 | lastCenter.y = centY; 301 | 302 | } 303 | popStyle(); 304 | } 305 | 306 | // ************************************************************ 307 | // CONVERT PIXEL STREAM BUFFER TO PIMAGE 308 | // ************************************************************ 309 | void buff2pixFrame(byte[][] pixBuff, PImage dstImg, request_t req) { 310 | 311 | int Y0 = 0, U = 0, Y1 = 0, V = 0; 312 | int Y2 = 0, Y3 = 0, Y4 = 0; 313 | int reqParam = req.getParam(); 314 | 315 | dstImg.loadPixels(); 316 | 317 | switch (req) { 318 | case STREAM0PPB: for (int y = 0, l = 0, x = 0; y < G_DEF.F_H; y++, x = 0) 319 | while (x < reqParam) { 320 | Y0 = int(pixBuff[y][x++]); 321 | U = int(pixBuff[y][x++]); 322 | Y1 = int(pixBuff[y][x++]); 323 | V = int(pixBuff[y][x++]); 324 | dstImg.pixels[l++] = YUV2RGB(Y0,U,V); 325 | dstImg.pixels[l++] = YUV2RGB(Y1,U,V); 326 | } 327 | break; 328 | case STREAM1PPB: for (int y = 0, l = 0, x = 0; y < G_DEF.F_H; y++, x = 0) 329 | while (x < reqParam) { 330 | Y0 = 0x08 | ((0x0f & int(pixBuff[y][x])) << 4); 331 | U = 0x00 | ((0xf0 & int(pixBuff[y][x++]))); 332 | Y1 = 0x08 | ((0x0f & int(pixBuff[y][x])) << 4); 333 | V = 0x00 | ((0xf0 & int(pixBuff[y][x++]))); 334 | dstImg.pixels[l++] = YUV2RGB(Y0,U,V); 335 | dstImg.pixels[l++] = YUV2RGB(Y1,U,V); 336 | } 337 | break; 338 | case STREAM2PPB: for (int y = 0, l = 0, x = 0; y < G_DEF.F_H; y++, x = 0) 339 | while (x < reqParam) { 340 | Y1 = int(pixBuff[y][x++]); 341 | Y0 = ((Y1 << 4) & 0xF0) | 0x1f; 342 | Y1 = (Y1 & 0xF0) | 0x1f; 343 | dstImg.pixels[l++] = color(Y0); 344 | dstImg.pixels[l++] = color(Y1); 345 | } 346 | break; 347 | case STREAM4PPB: for (int y = 0, l = 0, x = 0; y < G_DEF.F_H; y++, x = 0) 348 | while (x < reqParam) { 349 | Y3 = int(pixBuff[y][x++]); 350 | Y0 = ((Y3 << 6) & 0xC0) | 0x1f; 351 | Y1 = ((Y3 << 4) & 0xC0) | 0x1f; 352 | Y2 = ((Y3 << 2) & 0xC0) | 0x1f; 353 | Y3 = (Y3 & 0xC0) | 0x1f; 354 | dstImg.pixels[l++] = color(Y0); 355 | dstImg.pixels[l++] = color(Y1); 356 | dstImg.pixels[l++] = color(Y2); 357 | dstImg.pixels[l++] = color(Y3); 358 | } 359 | break; 360 | case STREAM8PPB: for (int y = 0, l = 0, x = 0; y < G_DEF.F_H; y++, x = 0) 361 | while (x < reqParam) { 362 | Y0 = int(pixBuff[y][x++]); 363 | 364 | dstImg.pixels[l++] = ((Y0 & 0x01) == 0? 0:0xffffff); 365 | dstImg.pixels[l++] = ((Y0 & 0x02) == 0? 0:0xffffff); 366 | dstImg.pixels[l++] = ((Y0 & 0x04) == 0? 0:0xffffff); 367 | dstImg.pixels[l++] = ((Y0 & 0x05) == 0? 0:0xffffff); 368 | dstImg.pixels[l++] = ((Y0 & 0x10) == 0? 0:0xffffff); 369 | dstImg.pixels[l++] = ((Y0 & 0x20) == 0? 0:0xffffff); 370 | dstImg.pixels[l++] = ((Y0 & 0x40) == 0? 0:0xffffff); 371 | dstImg.pixels[l++] = ((Y0 & 0x80) == 0? 0:0xffffff); 372 | } 373 | break; 374 | } 375 | dstImg.updatePixels(); 376 | } 377 | 378 | // ************************************************************ 379 | // YUV TO RGB 380 | // ************************************************************ 381 | 382 | color YUV2RGB(int Y, int Cb, int Cr) { 383 | // from OV7670 Software Application note 384 | float R = Y + 1.371*(Cr-128); 385 | float G = Y - 0.698*(Cr-128)+0.336*(Cb-128); 386 | float B = Y + 1.732*(Cb-128); 387 | 388 | return color(R, G, B); 389 | } 390 | 391 | // ************************************************************ 392 | // RGB TO YUV 393 | // ************************************************************ 394 | 395 | color RGB2YUV(int R, int G, int B) { 396 | // from OV7670 Software Application note 397 | float Yu = 0.299*R+0.587*G+0.114*B; 398 | float Cb = 0.568*(B-Y)+128; 399 | float Cr = 0.713*(R-Y)+128; 400 | 401 | return color(Yu, Cb, Cr); 402 | } 403 | // ************************************************************ 404 | // 405 | // ************************************************************ 406 | void keyPressed() { 407 | 408 | switch (key) { 409 | case ' ': int i = request.ordinal()+1; 410 | if (i >= request_t.values().length) i=0; 411 | request = request_t.values()[i]; 412 | serialPort.clear(); 413 | reqStatus = requestStatus_t.IDLE; 414 | 415 | break; 416 | case 'k': bKalmanEnabled = !bKalmanEnabled; 417 | break; 418 | case '+': thresh++; 419 | break; 420 | case '-': thresh--; 421 | break; 422 | case 's': saveFrame(); break; 423 | default: break; 424 | } 425 | 426 | } 427 | // ************************************************************ 428 | // 429 | // ************************************************************ 430 | 431 | void mousePressed() { 432 | println(mouseY); 433 | } 434 | -------------------------------------------------------------------------------- /arduvision_01/processing/receive_stream/simpleKalman.java: -------------------------------------------------------------------------------- 1 | //---------------- 2 | // adapted from code found here: 3 | // http://trandi.wordpress.com/2011/05/16/kalman-filter-simplified-version/ 4 | // 5 | public class simpleKalman { 6 | private double Q = 0.0001; 7 | private double R = 0.00025; 8 | private double P = 1, X = 0, K; 9 | 10 | private void measurementUpdate(){ 11 | K = (P + Q) / (P + Q + R); 12 | P = R * (P + Q) / (R + P + Q); 13 | } 14 | 15 | public double update(double measurement){ 16 | measurementUpdate(); 17 | double result = X + (measurement - X) * K; 18 | X = result; 19 | 20 | return result; 21 | } 22 | } 23 | //--------------- 24 | 25 | -------------------------------------------------------------------------------- /arduvision_02_mega/arduino/ov_fifo_test_mega/IO_config.h: -------------------------------------------------------------------------------- 1 | 2 | /******************************************************************* 3 | * 4 | * by David Sanz Kirbis 5 | * 6 | * Defines ports and pins used to connect an omnivision sensor+al422 7 | * fifo camera module to an Mega2560 Arduino clone board. 8 | * The module tested with this setup has a 12MHz clock connected to 9 | * the sensor XCLK and the following header / pinout: 10 | * 11 | * GND --- 1 2 --- VCC3.3 12 | * OV_SCL --- 3 4 --- FIFO_WRST 13 | * OV_SDA --- 5 6 --- FIFO_RRST 14 | * FIFO_D0 --- 7 8 --- FIFO_OE 15 | * FIFO_D2 --- 9 10 --- FIFO_D1 16 | * FIFO_D4 --- 11 12 --- FIFO_D3 17 | * FIFO_D6 --- 13 14 --- FIFO_D5 18 | * FIFO_RCLK --- 15 16 --- FIFO_D7 19 | * FIFO_WEN --- 17 18 --- OV_VSYNC 20 | * 21 | * 22 | * The definitions and implementation design is based on: 23 | * arndtjenssen's ov7670_ports.h (Aug 18, 2013) 24 | * see: https://github.com/arndtjenssen/ov7670 25 | * 26 | * 2014 Aug 19 - Modified original file to be used with an 27 | * Atmega 328p 28 | * Aug 21 - Changed pin mapping to put all data pins in 29 | * the same port, to save 1/3rd of the time employed 30 | * to read data from the fifo IC (i.e., to read each 31 | * whole byte in just one instruction). 32 | * The LS bits of the pixel data coming from the modules 33 | * are discarded in order to be able to communicate to 34 | * the 328p through the hardware UART TX and RX pins 35 | * and allow uploding Arduino sketches. 36 | * Also, interrupt pin INT0 is kept available. 37 | * The resulting image quality shows the expected 38 | * banding due to the reduction of depth but it is 39 | * fair enough for detection purposes. 40 | * 41 | * 2016 June 21 - Modified pin mapping for Mega2560 42 | * 43 | * 44 | * Wire the module as follows: 45 | * 46 | * 47 | * WARNING!!!! : sensor works at 3.3V USE A VOLTAGE LEVEL TRANSLATOR 48 | * 49 | * OV+FIFO ----------------------- ATMEGA 2560 (3.3V/8MHz) 50 | * 51 | * GND ----------------------- GND 52 | * 3.3v ----------------------- 3.3v 53 | * FIFO_OE ----------------------> GND 54 | * FIFO_WEN --> level tranlator --> PH5 / D8 55 | * FIFO_RCLK --> level tranlator --> PH6 / D9 /PWM 56 | * FIFO_WRST --> level tranlator --> PB6 / D12 57 | * FIFO_RRST --> level tranlator --> PB7 / D13 58 | * OV_SDA <-> level tranlator <-> PD1 / SDA 59 | * OV_SCL <-> level tranlator <-> PD0 / SCL 60 | * OV_VSYNC <-- level tranlator <-- PE4 / D2 61 | * FIFO_D3 <-- level tranlator <-- PF3 / A3 62 | * FIFO_D4 <-- level tranlator <-- PF4 / A4 63 | * FIFO_D5 <-- level tranlator <-- PF5 / A5 64 | * FIFO_D6 <-- level tranlator <-- PF6 / A6 65 | * FIFO_D7 <-- level tranlator <-- PF7 / A7 66 | * 67 | * 68 | * 69 | ********************************************/ 70 | 71 | #ifndef IO_CONFIG_H_ 72 | #define IO_CONFIG_H_ 73 | 74 | 75 | // data pins -------------------- 76 | 77 | #define DATA_DDR DDRF 78 | #define DATA_PORT PORTF 79 | #define DATA_PINS PINF 80 | 81 | // control pins -------------------- 82 | #define VSYNC_INT 0 83 | 84 | #ifdef VSYNC_INT 85 | #define OV_VSYNC _BV(PINE4) 86 | #else 87 | #define OV_VSYNC _BV(PINE5) 88 | #endif 89 | 90 | #define FIFO_WREN _BV(PINH5) // Write Enable (active low) 91 | #define FIFO_RCLK _BV(PINH6) // Read clock 92 | #define FIFO_WRST _BV(PINB6) // Write Reset (active low) 93 | #define FIFO_RRST _BV(PINB7) // Read Reset (active low) 94 | 95 | #define WREN_DDR DDRH 96 | #define WREN_PORT PORTH 97 | 98 | #define RCLK_DDR DDRH 99 | #define RCLK_PORT PORTH 100 | 101 | #define WRST_DDR DDRB 102 | #define WRST_PORT PORTB 103 | 104 | #define RRST_DDR DDRB 105 | #define RRST_PORT PORTB 106 | 107 | #ifdef VSYNC_INT 108 | #define VSYNC_PIN PINE 109 | #define VSYNC_DDR DDRE 110 | #define VSYNC_PORT PORTE 111 | #else 112 | #define VSYNC_PIN PINE 113 | #define VSYNC_DDR DDRE 114 | #define VSYNC_PORT PORTE 115 | #endif 116 | 117 | #define GET_VSYNC (VSYNC_PIN & OV_VSYNC) 118 | 119 | #define DISABLE_RRST RRST_PORT|=FIFO_RRST 120 | #define ENABLE_RRST RRST_PORT&=~FIFO_RRST 121 | 122 | #define DISABLE_WRST WRST_PORT|=FIFO_WRST 123 | #define ENABLE_WRST WRST_PORT&=~FIFO_WRST 124 | 125 | #define SET_RCLK_H RCLK_PORT|=FIFO_RCLK 126 | #define SET_RCLK_L RCLK_PORT&=~FIFO_RCLK 127 | 128 | #define ENABLE_WREN WREN_PORT |= FIFO_WREN 129 | #define DISABLE_WREN WREN_PORT &= ~FIFO_WREN 130 | 131 | 132 | // ************************************* 133 | void static inline setup_IO_ports() { 134 | 135 | // reset registers and register directions 136 | //DDRB = DDRD = DDRE = DDRH = DDRF = PORTB = PORTD = PORTE = PORTH = PORTF = 0; 137 | // set fifo data pins as inputs 138 | DATA_DDR = 0; // set pins as INPUTS 139 | 140 | WREN_DDR |= FIFO_WREN; // set pin as OUTPUT 141 | RCLK_DDR |= FIFO_RCLK; // set pin as OUTPUT 142 | RRST_DDR |= FIFO_RRST; // set pin as OUTPUT 143 | WRST_DDR |= FIFO_WRST; // set pin as OUTPUT 144 | 145 | VSYNC_DDR &= ~(OV_VSYNC); // set pin as INPUT 146 | #ifdef VSYNC_INT 147 | VSYNC_PORT |= OV_VSYNC; // enable pullup (for interruption handler) 148 | #endif 149 | } 150 | 151 | 152 | #endif /* IO_CONFIG_H_ */ 153 | -------------------------------------------------------------------------------- /arduvision_02_mega/arduino/ov_fifo_test_mega/delay.h: -------------------------------------------------------------------------------- 1 | /* 2 | * delay.h 3 | * 4 | * Provides accurate delays for a given number of nanoseconds 5 | * This version is part of the Arduino GLCD library. 6 | * 7 | * This file is based on code by Copyright Hans-Juergen Heinrichs (c) 2005 8 | * 9 | * the following comment is from his file 10 | * The idea for the functions below was heavily inspired by the 11 | * file which is part of the excellent WinAVR 12 | * distribution. Therefore, thanks to Marek Michalkiewicz and 13 | * Joerg Wunsch. 14 | * 15 | * The idea is to have the GCC preprocessor handle all calculations 16 | * necessary for determining the exact implementation of a delay 17 | * algorithm. The implementation itself is then inlined into the 18 | * user code. 19 | * In this way it is possible to always get the code size optimized 20 | * delay implementation. 21 | * 22 | */ 23 | 24 | /* 25 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 26 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 27 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 28 | ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 29 | LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 30 | CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 31 | SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 32 | INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 33 | CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 34 | ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 35 | POSSIBILITY OF SUCH DAMAGE. 36 | */ 37 | 38 | 39 | #ifndef _ARDUINO_DELAY_H_ 40 | #define _ARDUINO_DELAY_H_ 41 | 42 | #ifndef F_CPU 43 | # warning "Macro F_CPU must be defined" 44 | #endif 45 | 46 | /* 47 | * Forward declaration for all functions with attribute 48 | * 'always_inline' enforces GCC to inline the code (even 49 | * if it would be better not to do so from optimization 50 | * perspective). 51 | * Without this attribute GCC is free to implement 52 | * inline code or not (using the keyword 'inline' 53 | * alone is not sufficient). 54 | * 55 | */ 56 | static __inline__ void _NOP1( void) __attribute__((always_inline)); 57 | static __inline__ void _NOP2( void) __attribute__((always_inline)); 58 | static __inline__ void _NOP3( void) __attribute__((always_inline)); 59 | static __inline__ void _NOP4( void) __attribute__((always_inline)); 60 | static __inline__ void _NOP5( void) __attribute__((always_inline)); 61 | static __inline__ void _NOP6( void) __attribute__((always_inline)); 62 | static __inline__ void _NOP7( void) __attribute__((always_inline)); 63 | static __inline__ void _NOP8( void) __attribute__((always_inline)); 64 | static __inline__ void _NOP9( void) __attribute__((always_inline)); 65 | static __inline__ void _NOP10(void) __attribute__((always_inline)); 66 | static __inline__ void _NOP11(void) __attribute__((always_inline)); 67 | static __inline__ void _NOP12(void) __attribute__((always_inline)); 68 | 69 | static __inline__ void _delay_loop_3( uint32_t) __attribute__((always_inline)); 70 | static __inline__ void _delay_loop_1_x( uint8_t) __attribute__((always_inline)); 71 | static __inline__ void _delay_loop_2_x(uint16_t) __attribute__((always_inline)); 72 | static __inline__ void _delay_loop_3_x(uint32_t) __attribute__((always_inline)); 73 | 74 | static __inline__ void _delay_cycles(const double) __attribute__((always_inline)); 75 | 76 | 77 | /* 78 | * _ N O P x ( void ) 79 | * 80 | * Code sized optimized NOPs - not using any registers 81 | * 82 | * These NOPs will be used for very short delays where 83 | * it is more code efficient than executing loops. 84 | * 85 | */ 86 | static __inline__ void _NOP1 (void) { __asm__ volatile ( "nop " "\n\t" ); } 87 | static __inline__ void _NOP2 (void) { __asm__ volatile ( "rjmp 1f" "\n\t" "1:" "\n\t" ); } 88 | static __inline__ void _NOP3 (void) { __asm__ volatile ( "lpm " "\n\t" ); } 89 | static __inline__ void _NOP4 (void) { _NOP3(); _NOP1(); } 90 | static __inline__ void _NOP5 (void) { _NOP3(); _NOP2(); } 91 | static __inline__ void _NOP6 (void) { _NOP3(); _NOP3(); } 92 | static __inline__ void _NOP7 (void) { _NOP3(); _NOP3(); _NOP1(); } 93 | static __inline__ void _NOP8 (void) { _NOP3(); _NOP3(); _NOP2(); } 94 | static __inline__ void _NOP9 (void) { _NOP3(); _NOP3(); _NOP3(); } 95 | static __inline__ void _NOP10(void) { _NOP3(); _NOP3(); _NOP3(); _NOP1(); } 96 | static __inline__ void _NOP11(void) { _NOP3(); _NOP3(); _NOP3(); _NOP2(); } 97 | static __inline__ void _NOP12(void) { _NOP3(); _NOP3(); _NOP3(); _NOP3(); } 98 | 99 | 100 | 101 | /* 102 | * _ d e l a y _ l o o p _ 3( uint32_t __count ) 103 | * 104 | * This delay loop is not used in the code below: It is 105 | * a supplement to the _delay_loop_1() and _delay_loop_2() 106 | * within standard WinAVR giving a wider 107 | * (32 bit) delay range. 108 | * 109 | */ 110 | static __inline__ void 111 | _delay_loop_3( uint32_t __count ) 112 | { 113 | __asm__ volatile ( 114 | "1: sbiw %A0,1" "\n\t" 115 | "sbc %C0,__zero_reg__" "\n\t" 116 | "sbc %D0,__zero_reg__" "\n\t" 117 | "brne 1b" 118 | : "=w" (__count) 119 | : "0" (__count) 120 | ); 121 | } 122 | 123 | 124 | /* 125 | * _ d e l a y _ l o o p _ 1 _ x( uint8_t __count ) 126 | * _ d e l a y _ l o o p _ 2 _ x( uint16_t __count ) 127 | * _ d e l a y _ l o o p _ 4 _ x( uint32_t __count ) 128 | * 129 | * These delay loops always have exactly 4(8) cycles per loop. 130 | * They use a 8/16/32 bit register counter respectively. 131 | * 132 | */ 133 | static __inline__ void /* exactly 4 cycles/loop, max 2**8 loops */ 134 | _delay_loop_1_x( uint8_t __n ) 135 | { /* cycles per loop */ 136 | __asm__ volatile ( /* __n..one zero */ 137 | "1: dec %0" "\n\t" /* 1 1 */ 138 | " breq 2f" "\n\t" /* 1 2 */ 139 | "2: brne 1b" "\n\t" /* 2 1 */ 140 | : "=r" (__n) /* ----- ----- */ 141 | : "0" (__n) /* 4 4 */ 142 | ); 143 | } 144 | 145 | static __inline__ void /* exactly 4 cycles/loop, max 2**16 loops */ 146 | _delay_loop_2_x( uint16_t __n ) 147 | { /* cycles per loop */ 148 | __asm__ volatile ( /* __n..one zero */ 149 | "1: sbiw %0,1" "\n\t" /* 2 2 */ 150 | " brne 1b " "\n\t" /* 2 1 */ 151 | " nop " "\n\t" /* 1 */ 152 | : "=w" (__n) /* ----- ----- */ 153 | : "0" (__n) /* 4 4 */ 154 | ); 155 | } 156 | 157 | static __inline__ void /* exactly 8 cycles/loop, max 2**32 loops */ 158 | _delay_loop_3_x( uint32_t __n ) 159 | { /* cycles per loop */ 160 | __asm__ volatile ( /* __n..one zero */ 161 | "1: sbiw %A0,1 " "\n\t" /* 2 2 */ 162 | " sbc %C0,__zero_reg__" "\n\t" /* 1 1 */ 163 | " sbc %D0,__zero_reg__" "\n\t" /* 1 1 */ 164 | " nop " "\n\t" /* 1 1 */ 165 | " breq 2f " "\n\t" /* 1 2 */ 166 | "2: brne 1b " "\n\t" /* 2 1 */ 167 | : "=w" (__n) /* ----- ----- */ 168 | : "0" (__n) /* 8 8 */ 169 | ); 170 | } 171 | 172 | 173 | /* 174 | * 175 | * _ d e l a y _ c y c l e s (double __ticks_d) 176 | * 177 | * Perform an accurate delay of a given number of processor cycles. 178 | * 179 | * All the floating point arithmetic will be handled by the 180 | * GCC Preprocessor and no floating point code will be generated. 181 | * Allthough the parameter __ticks_d is of type 'double' this 182 | * function can be called with any constant integer value, too. 183 | * GCC will handle the casting appropriately. 184 | * 185 | * With an 8 MHz clock e.g., delays ranging from 125 nanoseconds 186 | * up to (2**32-1) * 125ns ~= 536,87 seconds are feasible. 187 | * 188 | */ 189 | static __inline__ void 190 | _delay_cycles(const double __ticks_d) 191 | { 192 | uint32_t __ticks = (uint32_t)(__ticks_d); 193 | uint32_t __padding; 194 | uint32_t __loops; 195 | 196 | /* 197 | * Special optimization for very 198 | * small delays - not using any register. 199 | */ 200 | if( __ticks <= 12 ) { /* this can be done with 4 opcodes */ 201 | __padding = __ticks; 202 | 203 | /* create a single byte counter */ 204 | } else if( __ticks <= 0x400 ) { 205 | __ticks -= 1; /* caller needs 1 cycle to init counter */ 206 | __loops = __ticks / 4; 207 | __padding = __ticks % 4; 208 | if( __loops != 0 ) 209 | _delay_loop_1_x( (uint8_t)__loops ); 210 | 211 | /* create a two byte counter */ 212 | } else if( __ticks <= 0x40001 ) { 213 | __ticks -= 2; /* caller needs 2 cycles to init counter */ 214 | __loops = __ticks / 4; 215 | __padding = __ticks % 4; 216 | if( __loops != 0 ) 217 | _delay_loop_2_x( (uint16_t)__loops ); 218 | 219 | /* create a four byte counter */ 220 | } else { 221 | __ticks -= 4; /* caller needs 4 cycles to init counter */ 222 | __loops = __ticks / 8; 223 | __padding = __ticks % 8; 224 | if( __loops != 0 ) 225 | _delay_loop_3_x( (uint32_t)__loops ); 226 | } 227 | 228 | if( __padding == 1 ) _NOP1(); 229 | if( __padding == 2 ) _NOP2(); 230 | if( __padding == 3 ) _NOP3(); 231 | if( __padding == 4 ) _NOP4(); 232 | if( __padding == 5 ) _NOP5(); 233 | if( __padding == 6 ) _NOP6(); 234 | if( __padding == 7 ) _NOP7(); 235 | if( __padding == 8 ) _NOP8(); 236 | if( __padding == 9 ) _NOP9(); 237 | if( __padding == 10 ) _NOP10(); 238 | if( __padding == 11 ) _NOP11(); 239 | if( __padding == 12 ) _NOP12(); 240 | } 241 | 242 | 243 | /* 244 | * _ d e l a y _ n s (double __ns) 245 | * _ d e l a y _ u s (double __us) 246 | * 247 | * Perform a very exact delay with a resolution as accurate as a 248 | * single CPU clock (the macro F_CPU is supposed to be defined to a 249 | * constant defining the CPU clock frequency in Hertz). 250 | * 251 | */ 252 | #define _delayNanoseconds(__ns) _delay_cycles( (double)(F_CPU)*((double)__ns)/1.0e9 + 0.5 ) 253 | #define _delayMicroseconds(__us) _delay_cycles( (double)(F_CPU)*((double)__us)/1.0e12 + 0.5 ) 254 | #define _delayMilliseconds(__ms) _delay_cycles( (double)(F_CPU)*((double)__ms)/1.0e15 + 0.5 ) 255 | 256 | #endif /* _ARDUINO_DELAY_H_ */ 257 | -------------------------------------------------------------------------------- /arduvision_02_mega/arduino/ov_fifo_test_mega/fifo.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "fifo.h" 3 | 4 | 5 | void fifo_loadFrame(void) 6 | { 7 | fifo_wrst(); 8 | // Capture frame 9 | // VSYNC is supposed to be set positive in the ov7725 (reg REG_COM10) 10 | while (!GET_VSYNC); // wait for an old frame to end 11 | while (GET_VSYNC); // wait for a new frame to start 12 | ENABLE_WREN; // enable writing to fifo 13 | while (!GET_VSYNC); // wait for the current frame to end 14 | DISABLE_WREN; // disable writing to fifo 15 | //wait(); 16 | DISABLE_RRST; 17 | } 18 | 19 | 20 | // Reset the fifo read pointer 21 | void fifo_rrst(void) 22 | { 23 | ENABLE_RRST; 24 | //_delayNanoseconds(5); 25 | SET_RCLK_H; 26 | //_delayNanoseconds(5); 27 | SET_RCLK_L; 28 | DISABLE_RRST; 29 | } 30 | //************************** 31 | 32 | // Reset the fifo write pointer 33 | void fifo_wrst(void) 34 | { 35 | DISABLE_WREN; 36 | _delayMicroseconds(1); 37 | ENABLE_WRST; 38 | _delayMicroseconds(1); 39 | DISABLE_WRST; 40 | } 41 | //************************** 42 | 43 | // Read one byte from the fifo 44 | uint8_t fifo_readByte(void) 45 | { 46 | uint8_t val; 47 | SET_RCLK_H; 48 | val = DATA_PINS; 49 | //_delay_cycles(10); 50 | SET_RCLK_L; 51 | //_delay_cycles(10); 52 | 53 | return val; 54 | } 55 | 56 | //************************** 57 | // 58 | // 59 | //************************** 60 | uint8_t fifo_readBytes(uint8_t *destBuf, unsigned long nBytes) 61 | { 62 | uint8_t *bufIndex = destBuf; 63 | 64 | while (nBytes > 0) { 65 | SET_RCLK_H; 66 | *bufIndex = DATA_PINS; 67 | //_delay_cycles(10); 68 | SET_RCLK_L; 69 | //_delay_cycles(10); 70 | bufIndex++; 71 | nBytes--; 72 | } 73 | return (nBytes == 0); 74 | } 75 | 76 | 77 | //************************** 78 | 79 | void fifo_sendSerialBytes(Stream &destPort, unsigned long nBytes) { 80 | 81 | uint8_t oneByte; 82 | // passing the serial por (Stream type) as a pointer would save memory ??? 83 | while (nBytes > 0) { 84 | // faster than passing the fifo_readByte() function to write() 85 | oneByte = fifo_readByte(); 86 | destPort.write(oneByte); //print((char)ov7725_read()); 87 | nBytes--; 88 | } 89 | } 90 | -------------------------------------------------------------------------------- /arduvision_02_mega/arduino/ov_fifo_test_mega/fifo.h: -------------------------------------------------------------------------------- 1 | 2 | #include 3 | #include "IO_config.h" 4 | #include "delay.h" 5 | 6 | void fifo_loadFrame(void); 7 | 8 | void fifo_rrst(void); 9 | void fifo_wrst(void); 10 | uint8_t fifo_readByte(void); 11 | void fifo_readStop(void); 12 | 13 | uint8_t fifo_readBytes(uint8_t *destBuf, unsigned long nBytes); 14 | 15 | void fifo_sendSerialBytes(Stream &destPort, unsigned long nBytes); 16 | 17 | // -------------------------------------- 18 | void __inline__ fifo_skipBytes(unsigned long nBytes) 19 | { 20 | while (nBytes > 0) { 21 | SET_RCLK_H; 22 | _delay_cycles(10); 23 | SET_RCLK_L; 24 | _delay_cycles(10); 25 | nBytes--; 26 | } 27 | } 28 | // -------------------------------------- 29 | static __inline__ void fifo_readRow0ppb(uint8_t* _rowStart, uint8_t* _rowEnd) 30 | { 31 | while (_rowStart != _rowEnd) { 32 | SET_RCLK_H; 33 | *_rowStart++ = DATA_PINS; 34 | //_delayNanoseconds(5); 35 | SET_RCLK_L; 36 | //_delayNanoseconds(5); 37 | } 38 | } 39 | // -------------------------------------- 40 | static __inline__ void fifo_readRow1ppb(uint8_t* _rowStart, uint8_t* _rowEnd) 41 | { 42 | uint8_t* _rowStart2 = _rowEnd; 43 | while (_rowStart != _rowEnd) { 44 | SET_RCLK_H; 45 | *_rowStart = DATA_PINS >> 4; 46 | *_rowStart2 = DATA_PINS >> 4; 47 | //_delayNanoseconds(5); 48 | SET_RCLK_L; 49 | //_delayNanoseconds(5); 50 | SET_RCLK_H; 51 | *_rowStart++ |= DATA_PINS & 0xf0; 52 | *_rowStart2++ |= DATA_PINS & 0xf0; 53 | //_delayNanoseconds(5); 54 | SET_RCLK_L; 55 | //_delayNanoseconds(5); 56 | } 57 | } 58 | // -------------------------------------- 59 | static __inline__ void fifo_readRow2ppb(uint8_t* _rowStart, uint8_t* _rowEnd) 60 | { 61 | uint8_t pixValue = 0; 62 | uint8_t dataValue = 0; 63 | while (_rowStart != _rowEnd) { 64 | 65 | SET_RCLK_H; 66 | pixValue = DATA_PINS >> 4; 67 | SET_RCLK_L; 68 | 69 | SET_RCLK_H; 70 | SET_RCLK_L; 71 | 72 | SET_RCLK_H; 73 | pixValue |= (DATA_PINS & 0xF0); 74 | SET_RCLK_L; 75 | 76 | SET_RCLK_H; 77 | SET_RCLK_L; 78 | 79 | *_rowStart++ = pixValue; 80 | } 81 | } 82 | // -------------------------------------- 83 | static __inline__ void fifo_readRow4ppb(uint8_t* _rowStart, uint8_t* _rowEnd) 84 | { 85 | uint8_t pixValue = 0; 86 | uint8_t dataValue = 0; 87 | while (_rowStart != _rowEnd) { 88 | 89 | SET_RCLK_H; 90 | pixValue = DATA_PINS >> 6; 91 | SET_RCLK_L; 92 | 93 | SET_RCLK_H; 94 | SET_RCLK_L; 95 | 96 | SET_RCLK_H; 97 | pixValue |= (DATA_PINS & 0xC0) >> 4; 98 | SET_RCLK_L; 99 | 100 | SET_RCLK_H; 101 | SET_RCLK_L; 102 | 103 | SET_RCLK_H; 104 | pixValue |= (DATA_PINS & 0xC0) >> 2; 105 | SET_RCLK_L; 106 | 107 | SET_RCLK_H; 108 | SET_RCLK_L; 109 | 110 | SET_RCLK_H; 111 | pixValue |= DATA_PINS & 0xC0; 112 | SET_RCLK_L; 113 | 114 | SET_RCLK_H; 115 | SET_RCLK_L; 116 | 117 | *_rowStart++ = pixValue; 118 | } 119 | } 120 | // -------------------------------------- 121 | static __inline__ void fifo_readRow8ppb(uint8_t* _rowStart, uint8_t* _rowEnd, uint8_t thresh) 122 | { 123 | uint8_t pixValue = 0; 124 | uint8_t bitIndex = 0; 125 | 126 | while (_rowStart != _rowEnd ) { 127 | //read "Y" byte 128 | SET_RCLK_H; 129 | pixValue |= (((DATA_PINS & 0xF8) > thresh) << bitIndex); 130 | SET_RCLK_L; 131 | 132 | // skip "U/V" byte 133 | SET_RCLK_H; 134 | SET_RCLK_L; 135 | bitIndex++; 136 | if (bitIndex == 8) { 137 | *_rowStart++ = pixValue; 138 | bitIndex = 0; 139 | pixValue = 0; 140 | } 141 | 142 | } 143 | } 144 | // -------------------------------------------- 145 | // -------------------------------------------- 146 | static __inline__ void fifo_getBrig(uint8_t* _rowStart, uint8_t _frW, uint8_t _frH, uint8_t _border, uint8_t _thresh) 147 | { 148 | 149 | } 150 | // -------------------------------------------- 151 | static __inline__ void fifo_getDark(uint8_t* _rowStart, uint8_t _frW, uint8_t _frH, uint8_t _border, uint8_t _thresh) 152 | { 153 | uint8_t i = 0; 154 | uint8_t j = 0; 155 | uint8_t pix = 255; 156 | uint8_t x0 = 255; 157 | uint8_t y0 = 255; 158 | uint8_t x1 = 0; 159 | uint8_t y1 = 0; 160 | uint8_t skipBytesX = _border * 2 ; // BPP 161 | uint8_t skipBytesX2 = skipBytesX * 2 + 2; 162 | uint16_t skipBytesY = (_border * _frW) * 2; // BPP 163 | 164 | _frH -= _border; 165 | _frW -= _border+1; 166 | 167 | fifo_skipBytes(skipBytesY); 168 | fifo_skipBytes(skipBytesX); 169 | for (j =_border; j < _frH; j++) { 170 | for (i =_border; i < _frW; i++) { 171 | // Y value of Nth pixel 172 | SET_RCLK_H; 173 | pix = DATA_PINS; 174 | SET_RCLK_L; 175 | if (pix < _thresh) { 176 | if (i > x1) x1 = i; 177 | else if (i < x0) x0 = i; 178 | if (y0 == 255) y0 = j; // first time only, y0 = 255 179 | y1 = j; 180 | } 181 | // skip "U/v" byte 182 | SET_RCLK_H; 183 | _delayNanoseconds(5); 184 | SET_RCLK_L; 185 | _delayNanoseconds(5); 186 | } 187 | fifo_skipBytes(skipBytesX2); 188 | } 189 | 190 | if ( (x0 < x1 ) && (y0 < y1 ) ) { 191 | *_rowStart++ = x0; 192 | *_rowStart++ = y0; 193 | *_rowStart++ = x1; 194 | *_rowStart++ = y1; 195 | } 196 | } 197 | // -------------------------------------- 198 | static __inline__ void fifo_loadFrameFast(void) 199 | { 200 | DISABLE_WREN; // disable writing to fifo 201 | 202 | ENABLE_WRST; 203 | //_delayNanoseconds(5); 204 | SET_RCLK_H; 205 | //_delayNanoseconds(5); 206 | SET_RCLK_L; 207 | DISABLE_WRST; 208 | _delay_cycles(10); 209 | while (!GET_VSYNC); // wait for an old frame to end 210 | while (GET_VSYNC); // wait for a new frame to start 211 | 212 | ENABLE_WREN; // enable writing to fifo 213 | while (!GET_VSYNC); // wait for the current frame to end 214 | 215 | ENABLE_RRST; 216 | //_delayNanoseconds(5); 217 | SET_RCLK_H; 218 | //_delayNanoseconds(5); 219 | SET_RCLK_L; 220 | DISABLE_RRST; 221 | } 222 | 223 | 224 | 225 | -------------------------------------------------------------------------------- /arduvision_02_mega/arduino/ov_fifo_test_mega/ov7670_regs.h: -------------------------------------------------------------------------------- 1 | /* 2 | * A V4L2 driver for OmniVision OV7670 cameras. 3 | * 4 | * Copyright 2006 One Laptop Per Child Association, Inc. Written 5 | * by Jonathan Corbet with substantial inspiration from Mark 6 | * McClelland's ovcamchip code. 7 | * 8 | * Copyright 2006-7 Jonathan Corbet 9 | * 10 | * This file may be distributed under the terms of the GNU General 11 | * Public License, version 2. 12 | 13 | * Aug 18, 2014 - Adapted by David Sanz Kirbis: 14 | */ 15 | 16 | 17 | 18 | #ifndef _OV7670_REGS_H 19 | #define _OV7670_REGS_H 20 | 21 | 22 | 23 | #include "sensor.h" 24 | 25 | 26 | #define OV7670_RD_ADDR 0x42 27 | #define OV7670_WR_ADDR 0x43 28 | 29 | #define VGA_WIDTH 640 30 | #define VGA_HEIGHT 480 31 | #define QVGA_WIDTH 320 32 | #define QVGA_HEIGHT 240 33 | #define QQVGA_WIDTH 160 34 | #define QQVGA_HEIGHT 120 35 | #define QQQVGA_WIDTH 80 36 | #define QQQVGA_HEIGHT 60 37 | #define CIF_WIDTH 352 38 | #define CIF_HEIGHT 288 39 | #define QCIF_WIDTH 176 40 | #define QCIF_HEIGHT 144 41 | 42 | 43 | // Control 1 44 | #define OV7670_REG_COM7 0x12 // Control 7 45 | #define COM7_RESET 0x80 // Register reset 46 | #define COM7_FMT_MASK 0x38 47 | #define COM7_FMT_VGA 0x00 48 | #define COM7_FMT_CIF 0x20 // CIF format 49 | #define COM7_FMT_QVGA 0x10 // QVGA format 50 | #define COM7_FMT_QCIF 0x08 // QCIF format 51 | #define COM7_RGB 0x04 // bits 0 and 2 - RGB format 52 | #define COM7_YUV 0x00 // YUV 53 | #define COM7_BAYER 0x01 // Bayer format 54 | #define COM7_PBAYER 0x05 // "Processed bayer" 55 | #define OV7670_REG_RGB444 0x8c // RGB 444 control 56 | #define R444_DISABLE 0x00 // Turn on RGB444, overrides 5x5 57 | #define R444_ENABLE 0x02 // Turn on RGB444, overrides 5x5 58 | #define R444_RGBX 0x01 // Empty nibble at end 59 | #define OV7670_REG_COM9 0x14 // Control 9 - gain ceiling 60 | #define OV7670_REG_COM10 0x15 // Control 10 61 | #define OV7670_REG_COM13 0x3d // Control 13 62 | #define COM13_GAMMA 0x80 // Gamma enable 63 | #define COM13_UVSAT 0x40 // UV saturation auto adjustment 64 | #define COM13_UVSWAP 0x01 // V before U - w/TSLB 65 | #define OV7670_REG_COM15 0x40 // Control 15 66 | #define COM15_R10F0 0x00 // Data range 10 to F0 67 | #define COM15_R01FE 0x80 // 01 to FE 68 | #define COM15_R00FF 0xc0 // 00 to FF 69 | #define COM15_RGB565 0x10 // RGB565 output 70 | #define COM15_RGB555 0x30 // RGB555 output 71 | #define OV7670_REG_COM11 0x3b // Control 11 72 | #define COM11_NIGHT 0x80 // NIght mode enable 73 | #define COM11_NMFR 0x60 // Two bit NM frame rate 74 | #define COM11_HZAUTO 0x10 // Auto detect 50/60 Hz 75 | #define COM11_50HZ 0x08 // Manual 50Hz select 76 | #define COM11_EXP 0x02 77 | #define OV7670_REG_COM17 0x42 // Control 17 78 | #define COM17_AECWIN 0xc0 // AEC window - must match COM4 79 | #define COM17_CBAR 0x08 // DSP Color bar 80 | #define OV7670_REG_TSLB 0x3a // lots of stuff 81 | #define TSLB_YLAST 0x04 // UYVY or VYUY - see com13 82 | #define TSLB_AUTO_OW 0x01 // Sensor automatically sets output window when resolution changes 83 | #define MTX1 0x4f // Matrix Coefficient 1 84 | #define MTX2 0x50 // Matrix Coefficient 2 85 | #define MTX3 0x51 // Matrix Coefficient 3 86 | #define MTX4 0x52 // Matrix Coefficient 4 87 | #define MTX5 0x53 // Matrix Coefficient 5 88 | #define MTX6 0x54 // Matrix Coefficient 6 89 | #define OV7670_REG_CONTRAS 0x56 // Contrast control 90 | #define MTXS 0x58 // Matrix Coefficient Sign 91 | #define AWBC7 0x59 // AWB Control 7 92 | #define AWBC8 0x5a // AWB Control 8 93 | #define AWBC9 0x5b // AWB Control 9 94 | #define AWBC10 0x5c // AWB Control 10 95 | #define AWBC11 0x5d // AWB Control 11 96 | #define AWBC12 0x5e // AWB Control 12 97 | #define OV7670_REG_GFIX 0x69 // Fix gain control 98 | #define GGAIN 0x6a // G Channel AWB Gain 99 | #define OV7670_REG_DBLV 0x6b // PLL control & internal regulator ( reg = on ) 100 | #define DBLV_X0 0x0A // Bypass PLL 101 | #define DBLV_X4 0x4A // Input clock x4 102 | #define DBLV_X6 0x8A // Input clock x6 103 | #define DBLV_X8 0xCA // Input clock x8 104 | #define AWBCTR3 0x6c // AWB Control 3 105 | #define AWBCTR2 0x6d // AWB Control 2 106 | #define AWBCTR1 0x6e // AWB Control 1 107 | #define AWBCTR0 0x6f // AWB Control 0 108 | #define OV7670_REG_COM8 0x13 // Control 8 109 | #define COM8_FASTAEC 0x80 // Enable fast AGC/AEC 110 | #define COM8_AECSTEP 0x40 // Unlimited AEC step size 111 | #define COM8_BFILT 0x20 // Band filter enable 112 | #define COM8_AGC 0x04 // Auto gain enable 113 | #define COM8_AWB 0x02 // White balance enable 114 | #define COM8_AEC 0x01 // Auto exposure enable 115 | #define OV7670_REG_COM3 0x0c // Control 3 116 | #define COM3_SWAP 0x40 // Byte swap 117 | #define COM3_SCALEEN 0x08 // Enable scaling 118 | #define COM3_DCWEN 0x04 // Enable downsamp/crop/window 119 | #define OV7670_REG_BRIGHT 0x55 // Brightness 120 | #define OV7670_REG_COM14 0x3e // Control 14 121 | #define COM14_DCWEN 0x10 // DCW/PCLK-scale enable 122 | #define COM14_PCLK_1 0x00 // PCLK Divided by 1 123 | #define COM14_PCLK_2 0x01 // PCLK Divided by 2 124 | #define COM14_PCLK_4 0x02 // PCLK Divided by 4 125 | #define COM14_PCLK_8 0x03 // PCLK Divided by 8 126 | #define COM14_PCLK_16 0x04 // PCLK Divided by 16 127 | #define OV7670_REG_HSTART 0x17 // Horiz start high bits 128 | #define OV7670_REG_HSTOP 0x18 // Horiz stop high bits 129 | #define OV7670_REG_VSTART 0x19 // Vert start high bits 130 | #define OV7670_REG_VSTOP 0x1a // Vert stop high bits 131 | #define OV7670_REG_HREF 0x32 // HREF pieces 132 | #define OV7670_REG_VREF 0x03 // Pieces of GAIN, VSTART, VSTOP 133 | // Registers 134 | #define OV7670_REG_GAIN 0x00 // Gain lower 8 bits (rest in vref) 135 | #define OV7670_REG_BLUE 0x01 // blue gain 136 | #define OV7670_REG_RED 0x02 // red gain 137 | #define OV7670_REG_VREF 0x03 // Pieces of GAIN, VSTART, VSTOP 138 | #define OV7670_REG_COM1 0x04 // Control 1 139 | #define COM1_CCIR656 0x40 // CCIR656 enable 140 | #define OV7670_REG_BAVE 0x05 // U/B Average level 141 | #define OV7670_REG_GbAVE 0x06 // Y/Gb Average level 142 | #define OV7670_REG_AECHH 0x07 // AEC MS 5 bits 143 | #define OV7670_REG_RAVE 0x08 // V/R Average level 144 | #define OV7670_REG_COM2 0x09 // Control 2 145 | #define COM2_SSLEEP 0x10 // Soft sleep mode 146 | #define OV7670_REG_PID 0x0a // Product ID MSB 147 | #define OV7670_REG_VER 0x0b // Product ID LSB 148 | #define OV7670_REG_COM3 0x0c // Control 3 149 | #define COM3_SWAP 0x40 // Byte swap 150 | #define COM3_SCALEEN 0x08 // Enable scaling 151 | #define COM3_DCWEN 0x04 // Enable downsamp/crop/window 152 | #define OV7670_REG_COM4 0x0d // Control 4 153 | #define OV7670_REG_COM5 0x0e // All "reserved" 154 | #define OV7670_REG_COM6 0x0f // Control 6 155 | #define OV7670_REG_AECH 0x10 // More bits of AEC value 156 | #define OV7670_REG_CLKRC 0x11 // Clocl control 157 | #define CLK_EXT 0x40 // Use external clock directly 158 | #define CLKRC_0 0x00 159 | #define CLKRC_2 0x01 // internal clock / 2 160 | #define CLKRC_3 0x02 // internal clock / 3 161 | #define CLKRC_4 0x03 // internal clock / 4 162 | #define CLKRC_5 0x04 // internal clock / 5 163 | #define CLKRC_6 0x05 // internal clock / 5 164 | #define CLK_SCALE 0x3f // Mask for internal clock scale 165 | #define OV7670_REG_COM7 0x12 // Control 7 166 | #define COM7_RESET 0x80 // Register reset 167 | #define COM7_FMT_MASK 0x38 168 | #define COM7_FMT_VGA 0x00 169 | #define COM7_FMT_CIF 0x20 // CIF format 170 | #define COM7_FMT_QVGA 0x10 // QVGA format 171 | #define COM7_FMT_QCIF 0x08 // QCIF format 172 | #define COM7_RGB 0x04 // bits 0 and 2 - RGB format 173 | #define COM7_YUV 0x00 // YUV 174 | #define COM7_BAYER 0x01 // Bayer format 175 | #define COM7_PBAYER 0x05 // "Processed bayer" 176 | #define OV7670_REG_COM8 0x13 // Control 8 177 | #define COM8_FASTAEC 0x80 // Enable fast AGC/AEC 178 | #define COM8_AECSTEP 0x40 // Unlimited AEC step size 179 | #define COM8_BFILT 0x20 // Band filter enable 180 | #define COM8_AGC 0x04 // Auto gain enable 181 | #define COM8_AWB 0x02 // White balance enable 182 | #define COM8_AEC 0x01 // Auto exposure enable 183 | #define OV7670_REG_COM9 0x14 // Control 9 - gain ceiling 184 | #define OV7670_REG_COM10 0x15 // Control 10 185 | #define COM10_HSYNC 0x40 // HSYNC instead of HREF 186 | #define COM10_PCLK_HB 0x20 // Suppress PCLK on horiz blank 187 | #define COM10_HREF_REV 0x08 // Reverse HREF 188 | #define COM10_VS_LEAD 0x04 // VSYNC on clock leading edge 189 | #define COM10_VS_NEG 0x02 // VSYNC negative 190 | #define COM10_HS_NEG 0x01 // HSYNC negative 191 | #define OV7670_REG_HSTART 0x17 // Horiz start high bits 192 | #define OV7670_REG_HSTOP 0x18 // Horiz stop high bits 193 | #define OV7670_REG_VSTART 0x19 // Vert start high bits 194 | #define OV7670_REG_VSTOP 0x1a // Vert stop high bits 195 | #define OV7670_REG_PSHFT 0x1b // Pixel delay after HREF 196 | #define OV7670_REG_MIDH 0x1c // Manuf. ID high 197 | #define OV7670_REG_MIDL 0x1d // Manuf. ID low 198 | #define OV7670_REG_MVFP 0x1e // Mirror / vflip 199 | #define MVFP_MIRROR 0x20 // Mirror image 200 | #define MVFP_FLIP 0x10 // Vertical flip 201 | 202 | #define OV7670_REG_AEW 0x24 // AGC upper limit 203 | #define OV7670_REG_AEB 0x25 // AGC lower limit 204 | #define OV7670_REG_VPT 0x26 // AGC/AEC fast mode op region 205 | #define OV7670_REG_HSYST 0x30 // HSYNC rising edge delay 206 | #define OV7670_REG_HSYEN 0x31 // HSYNC falling edge delay 207 | #define OV7670_REG_HREF 0x32 // HREF pieces 208 | #define OV7670_REG_TSLB 0x3a // lots of stuff 209 | #define TSLB_YLAST 0x04 // UYVY or VYUY - see com13 210 | #define TSLB_AUTO_OW 0x01 // Sensor automatically sets output window when resolution changes 211 | #define OV7670_REG_COM11 0x3b // Control 11 212 | #define COM11_NIGHT 0x80 // NIght mode enable 213 | #define COM11_NMFR 0x60 // Two bit NM frame rate 214 | #define COM11_HZAUTO 0x10 // Auto detect 50/60 Hz 215 | #define COM11_50HZ 0x08 // Manual 50Hz select 216 | #define COM11_EXP 0x02 217 | #define OV7670_REG_COM12 0x3c // Control 12 218 | #define COM12_HREF 0x80 // HREF always 219 | #define OV7670_REG_COM13 0x3d // Control 13 220 | #define COM13_GAMMA 0x80 // Gamma enable 221 | #define COM13_UVSAT 0b11001000 // UV saturation auto adjustment 222 | #define COM13_UVSWAP 0x01 // V before U - w/TSLB 223 | #define COM13_RSVD 0x08 224 | #define OV7670_REG_COM14 0x3e // Control 14 225 | #define COM14_DCWEN 0x10 // DCW/PCLK-scale enable 226 | #define COM14_DCW_MSCL 0x08 // Manual scaling 227 | #define COM14_PCLK_DIV_2 0x01 // divide pclk by 2 228 | #define COM14_PCLK_DIV_4 0x02 // divide pclk by 4 229 | #define COM14_PCLK_DIV_8 0x03 // divide pclk by 8 230 | #define COM14_PCLK_DIV_16 0x04 // divide pclk by 16 231 | 232 | #define OV7670_REG_EDGE 0x3f // Edge enhancement factor 233 | #define OV7670_REG_COM15 0x40 // Control 15 234 | #define COM15_R10F0 0x00 // Data range 10 to F0 235 | #define COM15_R01FE 0x80 // 01 to FE 236 | #define COM15_R00FF 0xc0 // 00 to FF 237 | #define COM15_RGB565 0x10 // RGB565 output 238 | #define COM15_RGB555 0x30 // RGB555 output 239 | #define OV7670_REG_COM16 0x41 // Control 16 240 | #define COM16_AWBGAIN 0x08 // AWB gain enable 241 | #define OV7670_REG_COM17 0x42 // Control 17 242 | #define COM17_AECWIN 0xc0 // AEC window - must match COM4 243 | #define COM17_CBAR 0x08 // DSP Color bar 244 | 245 | #define OV7670_REG_SCALING_XSC 0x70 // Bit[6:0]: Horizontal scale factor, def 3A 246 | #define OV7670_REG_SCALING_YSC 0x71 // Bit[6:0]: Vertical scale factor, def 35 247 | 248 | 249 | #define OV7670_REG_SCALING_DCWCTR 0x72 250 | #define SCALING_DCWCTR_2 0x11 // downsample by 2 251 | #define SCALING_DCWCTR_4 0x22 // downsample by 4 252 | #define SCALING_DCWCTR_8 0x33 // downsample by 8 253 | 254 | #define OV7670_REG_SCALING_PCLK_DIV 0x73 255 | #define SCALING_PCLK_DIV_1 0x00 256 | #define SCALING_PCLK_DIV_2 0x01 257 | #define SCALING_PCLK_DIV_4 0x02 258 | #define SCALING_PCLK_DIV_8 0x03 259 | #define SCALING_PCLK_DIV_16 0x04 260 | 261 | #define OV7670_REG_SCALING_PCLK_DELAY 0xA2 // Bit[6:0]: Scaling output delay, def 0x02 262 | 263 | #define OV7670_REG_SATCTR 0xC9 264 | 265 | 266 | /* 267 | * This matrix defines how the colors are generated, must be 268 | * tweaked to adjust hue and saturation. 269 | * 270 | * Order: v-red, v-green, v-blue, u-red, u-green, u-blue 271 | * 272 | * They are nine-bit signed quantities, with the sign bit 273 | * stored in 0x58. Sign for v-red is bit 0, and up from there. 274 | */ 275 | #define OV7670_REG_CMATRIX_BASE 0x4f 276 | #define CMATRIX_LEN 6 277 | #define OV7670_REG_CMATRIX_SIGN 0x58 278 | 279 | 280 | #define OV7670_REG_BRIGHT 0x55 /* Brightness */ 281 | #define OV7670_REG_CONTRAS 0x56 /* Contrast control */ 282 | 283 | #define OV7670_REG_GFIX 0x69 /* Fix gain control */ 284 | 285 | #define OV7670_REG_REG76 0x76 /* OV's name */ 286 | #define R76_BLKPCOR 0x81 /* Black pixel correction enable */ 287 | #define R76_WHTPCOR 0x41 /* White pixel correction enable */ 288 | 289 | #define OV7670_REG_RGB444 0x8c /* RGB 444 control */ 290 | #define R444_ENABLE 0x02 /* Turn on RGB444, overrides 5x5 */ 291 | #define R444_RGBX 0x01 /* Empty nibble at end */ 292 | 293 | #define OV7670_REG_HAECC1 0x9f /* Hist AEC/AGC control 1 */ 294 | #define OV7670_REG_HAECC2 0xa0 /* Hist AEC/AGC control 2 */ 295 | 296 | #define OV7670_REG_BD50MAX 0xa5 /* 50hz banding step limit */ 297 | #define OV7670_REG_HAECC3 0xa6 /* Hist AEC/AGC control 3 */ 298 | #define OV7670_REG_HAECC4 0xa7 /* Hist AEC/AGC control 4 */ 299 | #define OV7670_REG_HAECC5 0xa8 /* Hist AEC/AGC control 5 */ 300 | #define OV7670_REG_HAECC6 0xa9 /* Hist AEC/AGC control 6 */ 301 | #define OV7670_REG_HAECC7 0xaa /* Hist AEC/AGC control 7 */ 302 | #define OV7670_REG_BD60MAX 0xab /* 60hz banding step limit */ 303 | 304 | 305 | const struct regval_list qqvga_yuv_ov7670[] PROGMEM = { 306 | 307 | {OV7670_REG_COM8, COM8_FASTAEC|COM8_AECSTEP|COM8_AGC|COM8_AEC|COM8_AWB }, 308 | 309 | {OV7670_REG_CLKRC, 0x80}, 310 | {OV7670_REG_COM11, 0x0A}, 311 | {OV7670_REG_COM7, 0x00}, // output format: yuv 312 | {OV7670_REG_COM15, 0xC0}, // 313 | 314 | // not even sure what all these do, gonna check the oscilloscope and go from there... 315 | {OV7670_REG_HSTART, 0x16}, 316 | {OV7670_REG_HSTOP, 0x04}, 317 | {OV7670_REG_HREF, 0x24}, 318 | {OV7670_REG_VSTART, 0x02}, 319 | {OV7670_REG_VSTOP, 0x7a}, 320 | {OV7670_REG_VREF, 0x0a}, 321 | {OV7670_REG_COM10, 0x02}, 322 | {OV7670_REG_COM3, 0x04}, 323 | {OV7670_REG_MVFP, 0x3f}, 324 | 325 | // 160x120 326 | {OV7670_REG_COM14, 0x1a}, // divide by 4 327 | {0x72, 0x22}, // downsample by 4 328 | {0x73, 0xf2}, // divide by 4 329 | 330 | // COLOR SETTING 331 | {0x4f, 0x80}, 332 | {0x50, 0x80}, 333 | {0x51, 0x00}, 334 | {0x52, 0x22}, 335 | {0x53, 0x5e}, 336 | {0x54, 0x80}, 337 | {0x56, 0x40}, 338 | {0x58, 0x9e}, 339 | {0x59, 0x88}, 340 | {0x5a, 0x88}, 341 | {0x5b, 0x44}, 342 | {0x5c, 0x67}, 343 | {0x5d, 0x49}, 344 | {0x5e, 0x0e}, 345 | {0x69, 0x00}, 346 | {0x6a, 0x40}, 347 | {0x6b, 0x0a}, 348 | {0x6c, 0x0a}, 349 | {0x6d, 0x55}, 350 | {0x6e, 0x11}, 351 | {0x6f, 0x9f}, 352 | {0xb0, 0x84}, 353 | { 0xff, 0xff } // END MARKER 354 | }; 355 | 356 | 357 | const struct regval_list qqqvga_yuv_ov7670[] PROGMEM = { 358 | 359 | {OV7670_REG_COM8, COM8_AEC|COM8_AWB }, 360 | // {OV7670_REG_COM8, COM8_FASTAEC|COM8_AECSTEP|COM8_AGC|COM8_AEC|COM8_AWB }, 361 | // {OV7670_REG_REG76, R76_BLKPCOR | R76_WHTPCOR }, 362 | // {OV7670_REG_COM13, COM13_UVSAT | COM13_GAMMA}, // enable auto UV saturation 363 | // {OV7670_REG_SATCTR, 0x60}, // set min satuation value 364 | 365 | // {OV7670_REG_CLKRC, CLKRC_4}, // 15fps (with 12MHz XCLK) 366 | // {OV7670_REG_DBLV, DBLV_X8}, // 15fps (with 12MHz XCLK) 367 | // {OV7670_REG_CLKRC, CLKRC_2}, // 30fps (with 12MHz XCLK) 368 | // {OV7670_REG_DBLV, DBLV_X4}, // 30fps (with 12MHz XCLK) 369 | {OV7670_REG_CLKRC, CLKRC_2}, // 30fps (with 12MHz XCLK) 370 | {OV7670_REG_DBLV, DBLV_X8}, // 30fps (with 12MHz XCLK) 371 | // {OV7670_REG_CLKRC, CLKRC_0}, // 45fps (with 12MHz XCLK) 372 | // {OV7670_REG_DBLV, DBLV_X6}, // 45fps (with 12MHz XCLK) 373 | 374 | // {OV7670_REG_COM7, 0x00}, // output format: yuv (is default) 375 | {OV7670_REG_COM15, 0x00}, // output range [10] to [F0] 376 | // {OV7670_REG_COM15, 0x80}, // output range [01] to [FE] 377 | // {OV7670_REG_COM15, 0xC0}, // output range [00] to [FF] (default) 378 | 379 | // full output window for 640x480 and proportional resolutions 380 | {OV7670_REG_HSTART, 0x16}, {OV7670_REG_HSTOP, 0x04}, {OV7670_REG_HREF, 0x24}, 381 | {OV7670_REG_VSTART, 0x02}, {OV7670_REG_VSTOP, 0x7a}, {OV7670_REG_VREF, 0x0a}, 382 | 383 | 384 | //------------ 385 | // edge enhancement regs: 386 | // 3F OV7670_REG_EDGE Edge Enhancement Adjustment Bit 387 | // [7:5]: Reserved, Bit 388 | // [4:0]: Edge enhancement factor 389 | // def 00 390 | //{OV7670_REG_EDGE, 0x0F}, 391 | //------------ 392 | // REG75 393 | // Bit[7:5]: Reserved 394 | // Bit[4:0]: Edge enhancement lower limit 395 | // {0x75, 0F} 396 | //------------ 397 | // Bit[7]: Black pixel correction: 0: Disable / 1: Enable 398 | // Bit[6]: White pixel correction: 0: Disable / 1: Enable 399 | // Bit[5]:Reserved 400 | // Bit[4:0]: Edge enhancement higher limit 401 | // {0x76, 01} REG76 402 | 403 | //test pattern 404 | // {0x70, 0x80}, 405 | // {0x71, 0x80}, 406 | // scale down to 80x60 407 | {OV7670_REG_COM14, COM14_DCWEN | COM14_PCLK_DIV_8 }, // divide by 8 408 | {OV7670_REG_SCALING_DCWCTR, SCALING_DCWCTR_8}, // downsample by 8 409 | {OV7670_REG_COM3, COM3_DCWEN}, // DCW enable, Scale enabled 410 | {OV7670_REG_SCALING_PCLK_DIV, SCALING_PCLK_DIV_8}, // divide by 8 411 | { 0xff, 0xff } // END MARKER 412 | 413 | }; 414 | 415 | 416 | const struct regval_list common_reglist_ov7670[] PROGMEM = {//from the linux driver 417 | 418 | { OV7670_REG_COM3, 0 }, { OV7670_REG_COM14, 0 }, 419 | /* Mystery scaling numbers */ 420 | { 0x70, 0x3a }, { 0x71, 0x35 }, 421 | { 0x72, 0x11 }, { 0x73, 0xf0 }, 422 | { 0xa2,/* 0x02 changed to 1*/1},{ OV7670_REG_COM10, 0x0 }, 423 | /* Gamma curve values */ 424 | { 0x7a, 0x20 }, { 0x7b, 0x10 }, 425 | { 0x7c, 0x1e }, { 0x7d, 0x35 }, 426 | { 0x7e, 0x5a }, { 0x7f, 0x69 }, 427 | { 0x80, 0x76 }, { 0x81, 0x80 }, 428 | { 0x82, 0x88 }, { 0x83, 0x8f }, 429 | { 0x84, 0x96 }, { 0x85, 0xa3 }, 430 | { 0x86, 0xaf }, { 0x87, 0xc4 }, 431 | { 0x88, 0xd7 }, { 0x89, 0xe8 }, 432 | /* AGC and AEC parameters. Note we start by disabling those features, 433 | then turn them only after tweaking the values. */ 434 | { OV7670_REG_COM8, COM8_FASTAEC | COM8_AECSTEP }, 435 | { OV7670_REG_GAIN, 0 }, { OV7670_REG_AECH, 0 }, 436 | { OV7670_REG_COM4, 0x40 }, /* magic reserved bit */ 437 | { OV7670_REG_COM9, 0x18 }, /* 4x gain + magic rsvd bit */ 438 | { OV7670_REG_BD50MAX, 0x05 }, { OV7670_REG_BD60MAX, 0x07 }, 439 | { OV7670_REG_AEW, 0x95 }, { OV7670_REG_AEB, 0x33 }, 440 | { OV7670_REG_VPT, 0xe3 }, { OV7670_REG_HAECC1, 0x78 }, 441 | { OV7670_REG_HAECC2, 0x68 }, { 0xa1, 0x03 }, /* magic */ 442 | { OV7670_REG_HAECC3, 0xd8 }, { OV7670_REG_HAECC4, 0xd8 }, 443 | { OV7670_REG_HAECC5, 0xf0 }, { OV7670_REG_HAECC6, 0x90 }, 444 | { OV7670_REG_HAECC7, 0x94 }, 445 | { OV7670_REG_COM8, COM8_FASTAEC|COM8_AECSTEP|COM8_AGC|COM8_AEC }, 446 | {0x30,0},{0x31,0},//disable some delays 447 | /* Almost all of these are magic "reserved" values. */ 448 | { OV7670_REG_COM5, 0x61 }, { OV7670_REG_COM6, 0x4b }, 449 | { 0x16, 0x02 }, { OV7670_REG_MVFP, 0x07 }, 450 | { 0x21, 0x02 }, { 0x22, 0x91 }, 451 | { 0x29, 0x07 }, { 0x33, 0x0b }, 452 | { 0x35, 0x0b }, { 0x37, 0x1d }, 453 | { 0x38, 0x71 }, { 0x39, 0x2a }, 454 | { OV7670_REG_COM12, 0x78 }, { 0x4d, 0x40 }, 455 | { 0x4e, 0x20 }, { OV7670_REG_GFIX, 0 }, 456 | /*{ 0x6b, 0x4a },*/ { 0x74,0x10}, 457 | { 0x8d, 0x4f }, { 0x8e, 0 }, 458 | { 0x8f, 0 }, { 0x90, 0 }, 459 | { 0x91, 0 }, { 0x96, 0 }, 460 | { 0x9a, 0 }, { 0xb0, 0x84 }, 461 | { 0xb1, 0x0c }, { 0xb2, 0x0e }, 462 | { 0xb3, 0x82 }, { 0xb8, 0x0a }, 463 | 464 | /* More reserved magic, some of which tweaks white balance */ 465 | { 0x43, 0x0a }, { 0x44, 0xf0 }, 466 | { 0x45, 0x34 }, { 0x46, 0x58 }, 467 | { 0x47, 0x28 }, { 0x48, 0x3a }, 468 | { 0x59, 0x88 }, { 0x5a, 0x88 }, 469 | { 0x5b, 0x44 }, { 0x5c, 0x67 }, 470 | { 0x5d, 0x49 }, { 0x5e, 0x0e }, 471 | { 0x6c, 0x0a }, { 0x6d, 0x55 }, 472 | { 0x6e, 0x11 }, { 0x6f, 0x9e }, /* it was 0x9F "9e for advance AWB" */ 473 | { 0x6a, 0x40 }, { OV7670_REG_BLUE, 0x40 }, 474 | { OV7670_REG_RED, 0x60 }, 475 | { OV7670_REG_COM8, COM8_FASTAEC|COM8_AECSTEP|COM8_AGC|COM8_AEC|COM8_AWB }, 476 | 477 | /* Matrix coefficients */ 478 | { 0x4f, 0x80 }, { 0x50, 0x80 }, 479 | { 0x51, 0 }, { 0x52, 0x22 }, 480 | { 0x53, 0x5e }, { 0x54, 0x80 }, 481 | { 0x58, 0x9e }, 482 | 483 | { OV7670_REG_COM16, COM16_AWBGAIN }, { OV7670_REG_EDGE, 0 }, 484 | { 0x75, 0x05 }, { OV7670_REG_REG76, 0xe1 }, 485 | { 0x4c, 0 }, { 0x77, 0x01 }, 486 | { OV7670_REG_COM13, /*0xc3*/0x48 }, { 0x4b, 0x09 }, 487 | { 0xc9, 0x60 }, /*{ OV7670_REG_COM16, 0x38 },*/ 488 | { 0x56, 0x40 }, 489 | 490 | { 0x34, 0x11 }, { OV7670_REG_COM11, COM11_EXP|COM11_HZAUTO }, 491 | { 0xa4, 0x82/*Wax 0x88*/ }, { 0x96, 0 }, 492 | { 0x97, 0x30 }, { 0x98, 0x20 }, 493 | { 0x99, 0x30 }, { 0x9a, 0x84 }, 494 | { 0x9b, 0x29 }, { 0x9c, 0x03 }, 495 | { 0x9d, 0x4c }, { 0x9e, 0x3f }, 496 | { 0x78, 0x04 }, 497 | 498 | /* Extra-weird stuff. Some sort of multiplexor register */ 499 | { 0x79, 0x01 }, { 0xc8, 0xf0 }, 500 | { 0x79, 0x0f }, { 0xc8, 0x00 }, 501 | { 0x79, 0x10 }, { 0xc8, 0x7e }, 502 | { 0x79, 0x0a }, { 0xc8, 0x80 }, 503 | { 0x79, 0x0b }, { 0xc8, 0x01 }, 504 | { 0x79, 0x0c }, { 0xc8, 0x0f }, 505 | { 0x79, 0x0d }, { 0xc8, 0x20 }, 506 | { 0x79, 0x09 }, { 0xc8, 0x80 }, 507 | { 0x79, 0x02 }, { 0xc8, 0xc0 }, 508 | { 0x79, 0x03 }, { 0xc8, 0x40 }, 509 | { 0x79, 0x05 }, { 0xc8, 0x30 }, 510 | { 0x79, 0x26 }, 511 | 512 | { 0xff, 0xff } // END MARKER 513 | }; 514 | 515 | 516 | #endif /* _OV7670_REGS_H */ 517 | 518 | 519 | -------------------------------------------------------------------------------- /arduvision_02_mega/arduino/ov_fifo_test_mega/ov772x_regs.h: -------------------------------------------------------------------------------- 1 | /* 2 | * A V4L2 driver for OmniVision ov7670 cameras. 3 | * 4 | * Copyright 2006 One Laptop Per Child Association, Inc. Written 5 | * by Jonathan Corbet with substantial inspiration from Mark 6 | * McClelland's ovcamchip code. 7 | * 8 | * Copyright 2006-7 Jonathan Corbet 9 | * 10 | * This file may be distributed under the terms of the GNU General 11 | * Public License, version 2. 12 | 13 | * Aug 18, 2014 - Adapted by David Sanz Kirbis: 14 | */ 15 | 16 | 17 | 18 | #ifndef _OV772x_REGS_H 19 | #define _OV772x_REGS_H 20 | 21 | 22 | 23 | #include "sensor.h" 24 | 25 | 26 | #define OV772x_RD_ADDR 0x42 27 | #define OV772x_WR_ADDR 0x43 28 | 29 | #define VGA_WIDTH 640 30 | #define VGA_HEIGHT 480 31 | #define QVGA_WIDTH 320 32 | #define QVGA_HEIGHT 240 33 | #define QQVGA_WIDTH 160 34 | #define QQVGA_HEIGHT 120 35 | #define QQQVGA_WIDTH 80 36 | #define QQQVGA_HEIGHT 60 37 | #define CIF_WIDTH 352 38 | #define CIF_HEIGHT 288 39 | #define QCIF_WIDTH 176 40 | #define QCIF_HEIGHT 144 41 | 42 | 43 | // register offset 44 | 45 | #define OV772x_REG_GAIN 0x00 // AGC - Gain control gain setting 46 | #define OV772x_REG_BLUE 0x01 // AWB - Blue channel gain setting 47 | #define OV772x_REG_RED 0x02 // AWB - Red channel gain setting 48 | #define OV772x_REG_GREEN 0x03 // AWB - Green channel gain setting 49 | #define OV772x_REG_COM1 0x04 // Common control 1 50 | #define OV772x_REG_BAVG 0x05 // U/B Average Level 51 | #define OV772x_REG_GAVG 0x06 // Y/Gb Average Level 52 | #define OV772x_REG_RAVG 0x07 // V/R Average Level 53 | #define OV772x_REG_AECH 0x08 // Exposure Value - AEC MSBs 54 | #define OV772x_REG_COM2 0x09 // Common control 2 55 | #define OV772x_REG_PID 0x0A // Product ID Number MSB 56 | #define OV772x_REG_VER 0x0B // Product ID Number LSB 57 | #define OV772x_REG_COM3 0x0C // Common control 3 58 | #define OV772x_REG_COM4 0x0D // Common control 4 59 | #define OV772x_REG_COM5 0x0E // Common control 5 60 | #define OV772x_REG_COM6 0x0F // Common control 6 61 | #define OV772x_REG_AEC 0x10 // Exposure Value 62 | #define OV772x_REG_CLKRC 0x11 // Internal clock 63 | #define OV772x_REG_COM7 0x12 // Common control 7 64 | #define OV772x_REG_COM8 0x13 // Common control 8 65 | #define OV772x_REG_COM9 0x14 // Common control 9 66 | #define OV772x_REG_COM10 0x15 // Common control 10 67 | #define OV772x_REG_REG16 0x16 // Register 16 68 | #define OV772x_REG_HSTART 0x17 // Horizontal sensor size 69 | #define OV772x_REG_HSIZE 0x18 // Horizontal frame (HREF column) end high 8-bit 70 | #define OV772x_REG_VSTART 0x19 // Vertical frame (row) start high 8-bit 71 | #define OV772x_REG_VSIZE 0x1A // Vertical sensor size 72 | #define OV772x_REG_PSHFT 0x1B // Data format - pixel delay select 73 | #define OV772x_REG_MIDH 0x1C // Manufacturer ID byte - high 74 | #define OV772x_REG_MIDL 0x1D // Manufacturer ID byte - low 75 | #define OV772x_REG_LAEC 0x1F // Fine AEC value 76 | #define OV772x_REG_COM11 0x20 // Common control 11 77 | #define OV772x_REG_BDBASE 0x22 // Banding filter Minimum AEC value 78 | #define OV772x_REG_DBSTEP 0x23 // Banding filter Maximum Setp 79 | #define OV772x_REG_AEW 0x24 // AGC/AEC - Stable operating region (upper limit) 80 | #define OV772x_REG_AEB 0x25 // AGC/AEC - Stable operating region (lower limit) 81 | #define OV772x_REG_VPT 0x26 // AGC/AEC Fast mode operating region 82 | #define OV772x_REG_REG28 0x28 // Register 28 83 | #define OV772x_REG_HOUTSIZE 0x29 // Horizontal data output size MSBs 84 | #define OV772x_REG_EXHCH 0x2A // Dummy pixel insert MSB 85 | #define OV772x_REG_EXHCL 0x2B // Dummy pixel insert LSB 86 | #define OV772x_REG_VOUTSIZE 0x2C // Vertical data output size MSBs 87 | #define OV772x_REG_ADVFL 0x2D // LSB of insert dummy lines in Vertical direction 88 | #define OV772x_REG_ADVFH 0x2E // MSG of insert dummy lines in Vertical direction 89 | #define OV772x_REG_YAVE 0x2F // Y/G Channel Average value 90 | #define OV772x_REG_LUMHTH 0x30 // Histogram AEC/AGC Luminance high level threshold 91 | #define OV772x_REG_LUMLTH 0x31 // Histogram AEC/AGC Luminance low level threshold 92 | #define OV772x_REG_HREF 0x32 // Image start and size control 93 | #define OV772x_REG_DM_LNL 0x33 // Dummy line low 8 bits 94 | #define OV772x_REG_DM_LNH 0x34 // Dummy line high 8 bits 95 | #define OV772x_REG_ADOFF_B 0x35 // AD offset compensation value for B channel 96 | #define OV772x_REG_ADOFF_R 0x36 // AD offset compensation value for R channel 97 | #define OV772x_REG_ADOFF_GB 0x37 // AD offset compensation value for Gb channel 98 | #define OV772x_REG_ADOFF_GR 0x38 // AD offset compensation value for Gr channel 99 | #define OV772x_REG_OFF_B 0x39 // Analog process B channel offset value 100 | #define OV772x_REG_OFF_R 0x3A // Analog process R channel offset value 101 | #define OV772x_REG_OFF_GB 0x3B // Analog process Gb channel offset value 102 | #define OV772x_REG_OFF_GR 0x3C // Analog process Gr channel offset value 103 | #define OV772x_REG_COM12 0x3D // Common control 12 104 | #define OV772x_REG_COM13 0x3E // Common control 13 105 | #define OV772x_REG_COM14 0x3F // Common control 14 106 | #define OV772x_REG_COM15 0x40 // Common control 15 107 | #define OV772x_REG_COM16 0x41 // Common control 16 108 | #define OV772x_REG_TGT_B 0x42 // BLC blue channel target value 109 | #define OV772x_REG_TGT_R 0x43 // BLC red channel target value 110 | #define OV772x_REG_TGT_GB 0x44 // BLC Gb channel target value 111 | #define OV772x_REG_TGT_GR 0x45 // BLC Gr channel target value 112 | // for ov7720 113 | #define OV772x_REG_LCC0 0x46 // Lens correction control 0 114 | #define OV772x_REG_LCC1 0x47 // Lens correction option 1 - X coordinate 115 | #define OV772x_REG_LCC2 0x48 // Lens correction option 2 - Y coordinate 116 | #define OV772x_REG_LCC3 0x49 // Lens correction option 3 117 | #define OV772x_REG_LCC4 0x4A // Lens correction option 4 - radius of the circular 118 | #define OV772x_REG_LCC5 0x4B // Lens correction option 5 119 | #define OV772x_REG_LCC6 0x4C // Lens correction option 6 120 | // for ov772x 121 | #define OV772x_REG_LC_CTR 0x46 // Lens correction control 122 | #define OV772x_REG_LC_XC 0x47 // X coordinate of lens correction center relative 123 | #define OV772x_REG_LC_YC 0x48 // Y coordinate of lens correction center relative 124 | #define OV772x_REG_LC_COEF 0x49 // Lens correction coefficient 125 | #define OV772x_REG_LC_RADI 0x4A // Lens correction radius 126 | #define OV772x_REG_LC_COEFB 0x4B // Lens B channel compensation coefficient 127 | #define OV772x_REG_LC_COEFR 0x4C // Lens R channel compensation coefficient 128 | 129 | #define OV772x_REG_FIXGAIN 0x4D // Analog fix gain amplifer 130 | #define OV772x_REG_AREF0 0x4E // Sensor reference control 131 | #define OV772x_REG_AREF1 0x4F // Sensor reference current control 132 | #define OV772x_REG_AREF2 0x50 // Analog reference control 133 | #define OV772x_REG_AREF3 0x51 // ADC reference control 134 | #define OV772x_REG_AREF4 0x52 // ADC reference control 135 | #define OV772x_REG_AREF5 0x53 // ADC reference control 136 | #define OV772x_REG_AREF6 0x54 // Analog reference control 137 | #define OV772x_REG_AREF7 0x55 // Analog reference control 138 | #define OV772x_REG_UFIX 0x60 // U channel fixed value output 139 | #define OV772x_REG_VFIX 0x61 // V channel fixed value output 140 | #define OV772x_REG_AWBB_BLK 0x62 // AWB option for advanced AWB 141 | #define OV772x_REG_AWB_CTRL0 0x63 // AWB control byte 0 142 | #define OV772x_REG_DSP_CTRL1 0x64 // DSP control byte 1 143 | #define OV772x_REG_DSP_CTRL2 0x65 // DSP control byte 2 144 | #define OV772x_REG_DSP_CTRL3 0x66 // DSP control byte 3 145 | #define OV772x_REG_DSP_CTRL4 0x67 // DSP control byte 4 146 | #define OV772x_REG_AWB_BIAS 0x68 // AWB BLC level clip 147 | #define OV772x_REG_AWB_CTRL1 0x69 // AWB control 1 148 | #define OV772x_REG_AWB_CTRL2 0x6A // AWB control 2 149 | #define OV772x_REG_AWB_CTRL3 0x6B // AWB control 3 150 | #define OV772x_REG_AWB_CTRL4 0x6C // AWB control 4 151 | #define OV772x_REG_AWB_CTRL5 0x6D // AWB control 5 152 | #define OV772x_REG_AWB_CTRL6 0x6E // AWB control 6 153 | #define OV772x_REG_AWB_CTRL7 0x6F // AWB control 7 154 | #define OV772x_REG_AWB_CTRL8 0x70 // AWB control 8 155 | #define OV772x_REG_AWB_CTRL9 0x71 // AWB control 9 156 | #define OV772x_REG_AWB_CTRL10 0x72 // AWB control 10 157 | #define OV772x_REG_AWB_CTRL11 0x73 // AWB control 11 158 | #define OV772x_REG_AWB_CTRL12 0x74 // AWB control 12 159 | #define OV772x_REG_AWB_CTRL13 0x75 // AWB control 13 160 | #define OV772x_REG_AWB_CTRL14 0x76 // AWB control 14 161 | #define OV772x_REG_AWB_CTRL15 0x77 // AWB control 15 162 | #define OV772x_REG_AWB_CTRL16 0x78 // AWB control 16 163 | #define OV772x_REG_AWB_CTRL17 0x79 // AWB control 17 164 | #define OV772x_REG_AWB_CTRL18 0x7A // AWB control 18 165 | #define OV772x_REG_AWB_CTRL19 0x7B // AWB control 19 166 | #define OV772x_REG_AWB_CTRL20 0x7C // AWB control 20 167 | #define OV772x_REG_AWB_CTRL21 0x7D // AWB control 21 168 | #define OV772x_REG_GAM1 0x7E // Gamma Curve 1st segment input end point 169 | #define OV772x_REG_GAM2 0x7F // Gamma Curve 2nd segment input end point 170 | #define OV772x_REG_GAM3 0x80 // Gamma Curve 3rd segment input end point 171 | #define OV772x_REG_GAM4 0x81 // Gamma Curve 4th segment input end point 172 | #define OV772x_REG_GAM5 0x82 // Gamma Curve 5th segment input end point 173 | #define OV772x_REG_GAM6 0x83 // Gamma Curve 6th segment input end point 174 | #define OV772x_REG_GAM7 0x84 // Gamma Curve 7th segment input end point 175 | #define OV772x_REG_GAM8 0x85 // Gamma Curve 8th segment input end point 176 | #define OV772x_REG_GAM9 0x86 // Gamma Curve 9th segment input end point 177 | #define OV772x_REG_GAM10 0x87 // Gamma Curve 10th segment input end point 178 | #define OV772x_REG_GAM11 0x88 // Gamma Curve 11th segment input end point 179 | #define OV772x_REG_GAM12 0x89 // Gamma Curve 12th segment input end point 180 | #define OV772x_REG_GAM13 0x8A // Gamma Curve 13th segment input end point 181 | #define OV772x_REG_GAM14 0x8B // Gamma Curve 14th segment input end point 182 | #define OV772x_REG_GAM15 0x8C // Gamma Curve 15th segment input end point 183 | #define OV772x_REG_SLOP 0x8D // Gamma curve highest segment slope 184 | #define OV772x_REG_DNSTH 0x8E // De-noise threshold 185 | #define OV772x_REG_EDGE_STRNGT 0x8F // Edge strength control when manual mode 186 | #define OV772x_REG_EDGE_TRSHLD 0x90 // Edge threshold control when manual mode 187 | #define OV772x_REG_DNSOFF 0x91 // Auto De-noise threshold control 188 | #define OV772x_REG_EDGE_UPPER 0x92 // Edge strength upper limit when Auto mode 189 | #define OV772x_REG_EDGE_LOWER 0x93 // Edge strength lower limit when Auto mode 190 | #define OV772x_REG_MTX1 0x94 // Matrix coefficient 1 191 | #define OV772x_REG_MTX2 0x95 // Matrix coefficient 2 192 | #define OV772x_REG_MTX3 0x96 // Matrix coefficient 3 193 | #define OV772x_REG_MTX4 0x97 // Matrix coefficient 4 194 | #define OV772x_REG_MTX5 0x98 // Matrix coefficient 5 195 | #define OV772x_REG_MTX6 0x99 // Matrix coefficient 6 196 | #define OV772x_REG_MTX_CTRL 0x9A // Matrix control 197 | #define OV772x_REG_BRIGHT 0x9B // Brightness control 198 | #define OV772x_REG_CNTRST 0x9C // Contrast contrast 199 | #define OV772x_REG_CNTRST_CTRL 0x9D // Contrast contrast center 200 | #define OV772x_REG_UVAD_J0 0x9E // Auto UV adjust contrast 0 201 | #define OV772x_REG_UVAD_J1 0x9F // Auto UV adjust contrast 1 202 | #define OV772x_REG_SCAL0 0xA0 // Scaling control 0 203 | #define OV772x_REG_SCAL1 0xA1 // Scaling control 1 204 | #define OV772x_REG_SCAL2 0xA2 // Scaling control 2 205 | #define OV772x_REG_FIFODLYM 0xA3 // FIFO manual mode delay control 206 | #define OV772x_REG_FIFODLYA 0xA4 // FIFO auto mode delay control 207 | #define OV772x_REG_SDE 0xA6 // Special digital effect control 208 | #define OV772x_REG_USAT 0xA7 // U component saturation control 209 | #define OV772x_REG_VSAT 0xA8 // V component saturation control 210 | // for ov7720 211 | #define OV772x_REG_HUE0 0xA9 // Hue control 0 212 | #define OV772x_REG_HUE1 0xAA // Hue control 1 213 | // for ov772x 214 | #define OV772x_REG_HUECOS 0xA9 // Cosine value 215 | #define OV772x_REG_HUESIN 0xAA // Sine value 216 | 217 | #define OV772x_REG_SIGN 0xAB // Sign bit for Hue and contrast 218 | #define OV772x_REG_DSPAUTO 0xAC // DSP auto function ON/OFF control 219 | 220 | // register detail 221 | 222 | 223 | // COM2 224 | #define OV772x_REG_SOFT_SLEEP_MODE 0x10 // Soft sleep mode 225 | // Output drive capability 226 | #define OV772x_REG_OCAP_1x 0x00 // 1x 227 | #define OV772x_REG_OCAP_2x 0x01 // 2x 228 | #define OV772x_REG_OCAP_3x 0x02 // 3x 229 | #define OV772x_REG_OCAP_4x 0x03 // 4x 230 | 231 | // COM3 232 | #define OV772x_REG_SWAP_MASK (SWAP_RGB | SWAP_YUV | SWAP_ML) 233 | #define OV772x_REG_IMG_MASK (VFLIP_IMG | HFLIP_IMG) 234 | 235 | #define OV772x_REG_VFLIP_IMG 0x80 // Vertical flip image ON/OFF selection 236 | #define OV772x_REG_HFLIP_IMG 0x40 // Horizontal mirror image ON/OFF selection 237 | #define OV772x_REG_SWAP_RGB 0x20 // Swap B/R output sequence in RGB mode 238 | #define OV772x_REG_SWAP_YUV 0x10 // Swap Y/UV output sequence in YUV mode 239 | #define OV772x_REG_SWAP_ML 0x08 // Swap output MSB/LSB 240 | // Tri-state option for output clock 241 | #define OV772x_REG_NOTRI_CLOCK 0x04 // 0: Tri-state at this period 242 | // 1: No tri-state at this period 243 | // Tri-state option for output data 244 | #define OV772x_REG_NOTRI_DATA 0x02 // 0: Tri-state at this period 245 | // 1: No tri-state at this period 246 | #define OV772x_REG_SCOLOR_TEST 0x01 // Sensor color bar test pattern 247 | 248 | // COM4 249 | // PLL frequency control 250 | #define OV772x_REG_PLL_BYPASS 0x00 // 00: Bypass PLL 251 | #define OV772x_REG_PLL_4x 0x40 // 01: PLL 4x 252 | #define OV772x_REG_PLL_6x 0x80 // 10: PLL 6x 253 | #define OV772x_REG_PLL_8x 0xc0 // 11: PLL 8x 254 | // AEC evaluate window 255 | #define OV772x_REG_AEC_FULL 0x00 // 00: Full window 256 | #define OV772x_REG_AEC_1p2 0x10 // 01: 1/2 window 257 | #define OV772x_REG_AEC_1p4 0x20 // 10: 1/4 window 258 | #define OV772x_REG_AEC_2p3 0x30 // 11: Low 2/3 window 259 | 260 | // COM5 261 | #define OV772x_REG_AFR_ON_OFF 0x80 // Auto frame rate control ON/OFF selection 262 | #define OV772x_REG_AFR_SPPED 0x40 // Auto frame rate control speed selection 263 | // Auto frame rate max rate control 264 | #define OV772x_REG_AFR_NO_RATE 0x00 // No reduction of frame rate 265 | #define OV772x_REG_AFR_1p2 0x10 // Max reduction to 1/2 frame rate 266 | #define OV772x_REG_AFR_1p4 0x20 // Max reduction to 1/4 frame rate 267 | #define OV772x_REG_AFR_1p8 0x30 // Max reduction to 1/8 frame rate 268 | // Auto frame rate active point control 269 | #define OV772x_REG_AF_2x 0x00 // Add frame when AGC reaches 2x gain 270 | #define OV772x_REG_AF_4x 0x04 // Add frame when AGC reaches 4x gain 271 | #define OV772x_REG_AF_8x 0x08 // Add frame when AGC reaches 8x gain 272 | #define OV772x_REG_AF_16x 0x0c // Add frame when AGC reaches 16x gain 273 | // AEC max step control 274 | #define OV772x_REG_AEC_NO_LIMIT 0x01 // 0 : AEC incease step has limit 275 | // 1 : No limit to AEC increase step 276 | 277 | // COM7 278 | // SCCB Register Reset 279 | #define OV772x_REG_SCCB_RESET 0x80 // 0 : No change 280 | // 1 : Resets all registers to default 281 | // Resolution selection 282 | #define OV772x_REG_SLCT_MASK 0x40 // Mask of VGA or QVGA 283 | #define OV772x_REG_SLCT_VGA 0x00 // 0 : VGA 284 | #define OV772x_REG_SLCT_QVGA 0x40 // 1 : QVGA 285 | #define OV772x_REG_ITU656_ON_OFF 0x20 // ITU656 protocol ON/OFF selection 286 | #define OV772x_REG_SENSOR_RAW 0x10 // Sensor RAW 287 | // RGB output format control 288 | #define OV772x_REG_FMT_MASK 0x0c // Mask of color format 289 | #define OV772x_REG_FMT_GBR422 0x00 // 00 : GBR 4:2:2 290 | #define OV772x_REG_FMT_RGB565 0x04 // 01 : RGB 565 291 | #define OV772x_REG_FMT_RGB555 0x08 // 10 : RGB 555 292 | #define OV772x_REG_FMT_RGB444 0x0c // 11 : RGB 444 293 | // Output format control 294 | #define OV772x_REG_OFMT_MASK 0x03 // Mask of output format 295 | #define OV772x_REG_OFMT_YUV 0x00 // 00 : YUV 296 | #define OV772x_REG_OFMT_P_BRAW 0x01 // 01 : Processed Bayer RAW 297 | #define OV772x_REG_OFMT_RGB 0x02 // 10 : RGB 298 | #define OV772x_REG_OFMT_BRAW 0x03 // 11 : Bayer RAW 299 | 300 | // COM8 301 | #define OV772x_REG_FAST_ALGO 0x80 // Enable fast AGC/AEC algorithm 302 | // AEC Setp size limit 303 | #define OV772x_REG_UNLMT_STEP 0x40 // 0 : Step size is limited 304 | // 1 : Unlimited step size 305 | #define OV772x_REG_BNDF_ON_OFF 0x20 // Banding filter ON/OFF 306 | #define OV772x_REG_AEC_BND 0x10 // Enable AEC below banding value 307 | #define OV772x_REG_AEC_ON_OFF 0x08 // Fine AEC ON/OFF control 308 | #define OV772x_REG_AGC_ON 0x04 // AGC Enable 309 | #define OV772x_REG_AWB_ON 0x02 // AWB Enable 310 | #define OV772x_REG_AEC_ON 0x01 // AEC Enable 311 | 312 | // COM9 313 | #define OV772x_REG_BASE_AECAGC 0x80 // Histogram or average based AEC/AGC 314 | // Automatic gain ceiling - maximum AGC value 315 | #define OV772x_REG_GAIN_2x 0x00 // 000 : 2x 316 | #define OV772x_REG_GAIN_4x 0x10 // 001 : 4x 317 | #define OV772x_REG_GAIN_8x 0x20 // 010 : 8x 318 | #define OV772x_REG_GAIN_16x 0x30 // 011 : 16x 319 | #define OV772x_REG_GAIN_32x 0x40 // 100 : 32x 320 | #define OV772x_REG_GAIN_64x 0x50 // 101 : 64x 321 | #define OV772x_REG_GAIN_128x 0x60 // 110 : 128x 322 | #define OV772x_REG_DROP_VSYNC 0x04 // Drop VSYNC output of corrupt frame 323 | #define OV772x_REG_DROP_HREF 0x02 // Drop HREF output of corrupt frame 324 | 325 | // COM11 326 | #define OV772x_REG_SGLF_ON_OFF 0x02 // Single frame ON/OFF selection 327 | #define OV772x_REG_SGLF_TRIG 0x01 // Single frame transfer trigger 328 | 329 | // HREF 330 | #define OV772x_REG_HREF_VSTART_SHIFT 6 // VSTART LSB 331 | #define OV772x_REG_HREF_HSTART_SHIFT 4 // HSTART 2 LSBs 332 | #define OV772x_REG_HREF_VSIZE_SHIFT 2 // VSIZE LSB 333 | #define OV772x_REG_HREF_HSIZE_SHIFT 0 // HSIZE 2 LSBs 334 | 335 | // EXHCH 336 | #define OV772x_REG_EXHCH_VSIZE_SHIFT 2 // VOUTSIZE LSB 337 | #define OV772x_REG_EXHCH_HSIZE_SHIFT 0 // HOUTSIZE 2 LSBs 338 | 339 | // DSP_CTRL1 340 | #define OV772x_REG_FIFO_ON 0x80 // FIFO enable/disable selection 341 | #define OV772x_REG_UV_ON_OFF 0x40 // UV adjust function ON/OFF selection 342 | #define OV772x_REG_YUV444_2_422 0x20 // YUV444 to 422 UV channel option selection 343 | #define OV772x_REG_CLR_MTRX_ON_OFF 0x10 // Color matrix ON/OFF selection 344 | #define OV772x_REG_INTPLT_ON_OFF 0x08 // Interpolation ON/OFF selection 345 | #define OV772x_REG_GMM_ON_OFF 0x04 // Gamma function ON/OFF selection 346 | #define OV772x_REG_AUTO_BLK_ON_OFF 0x02 // Black defect auto correction ON/OFF 347 | #define OV772x_REG_AUTO_WHT_ON_OFF 0x01 // White define auto correction ON/OFF 348 | 349 | // DSP_CTRL3 350 | #define OV772x_REG_UV_MASK 0x80 // UV output sequence option 351 | #define OV772x_REG_UV_ON 0x80 // ON 352 | #define OV772x_REG_UV_OFF 0x00 // OFF 353 | #define OV772x_REG_CBAR_MASK 0x20 // DSP Color bar mask 354 | #define OV772x_REG_CBAR_ON 0x20 // ON 355 | #define OV772x_REG_CBAR_OFF 0x00 // OFF 356 | 357 | // DSP_CTRL4 358 | #define OV772x_REG_DSP_OFMT_YUV 0x00 359 | #define OV772x_REG_DSP_OFMT_RGB 0x00 360 | #define OV772x_REG_DSP_OFMT_RAW8 0x02 361 | #define OV772x_REG_DSP_OFMT_RAW10 0x03 362 | 363 | // DSPAUTO (DSP Auto Function ON/OFF Control) 364 | #define OV772x_REG_AWB_ACTRL 0x80 // AWB auto threshold control 365 | #define OV772x_REG_DENOISE_ACTRL 0x40 // De-noise auto threshold control 366 | #define OV772x_REG_EDGE_ACTRL 0x20 // Edge enhancement auto strength control 367 | #define OV772x_REG_UV_ACTRL 0x10 // UV adjust auto slope control 368 | #define OV772x_REG_SCAL0_ACTRL 0x08 // Auto scaling factor control 369 | #define OV772x_REG_SCAL1_2_ACTRL 0x04 // Auto scaling factor control 370 | 371 | 372 | 373 | const struct regval_list qqvga_yuv_ov772x[] PROGMEM = { 374 | 375 | {OV772x_REG_COM7, OV772x_REG_SLCT_VGA}, // QVGA, YUY 376 | {OV772x_REG_COM12, 0x03}, // DC offset compensation for analog process 377 | {0x11, 0x01}, // 00/01/03/07 for 60/30/15/7.5fps - set to 30fps for QQVGA 378 | 379 | {OV772x_REG_DSP_CTRL2, 0x2f}, // DCW enable, zoom out enable 380 | 381 | // 160x120 382 | {0xA0, 0x0a}, // SCAL0, 1/4 vertical & horizontal down sampling 383 | {0xA1, 0x40}, // SCAL1, Horizontal Zoom Out Control, set ratio to 1/1 384 | {0xA2, 0x40}, // SCAL2, Vertical Zoom Out Control, set ratio to 1/1 385 | 386 | {OV772x_REG_HSTART, 0x23}, 387 | {OV772x_REG_HSIZE, 0xa0}, // Horizontal Sensor Size: full VGA (no windowing) 388 | {0x29, 0x28}, // Horizontal Data Output Size (160px) MSBs 389 | {OV772x_REG_VSTART, 0x07}, 390 | {OV772x_REG_VSIZE, 0xf0}, // Vertical Sensor Size: full VGA (no windowing) 391 | {0x2c, 0x3c}, // Vertical Data Output Size (120px)MSBs 392 | {OV772x_REG_HREF, 0x00}, 393 | {0x2a, 0x00}, // EXHCH 394 | {0x15,0x01}, // Output data range selection, Data from [10] to [F0] (8 MSBs) 395 | 396 | { 0xff, 0xff } // END MARKER 397 | 398 | }; 399 | 400 | const struct regval_list qqqvga_yuv_ov772x[] PROGMEM = { 401 | 402 | {OV772x_REG_COM7, OV772x_REG_SLCT_VGA}, // QVGA, YUY 403 | {OV772x_REG_COM12, 0x03}, // DC offset compensation for analog process 404 | {0x11, 0x01}, // 00/01/03/07 for 60/30/15/7.5fps - set to 30fps for QQVGA 405 | 406 | {OV772x_REG_DSP_CTRL2, 0x0f}, // 0x2f // DCW enable, zoom out enable 407 | 408 | {0xA0, 0x0f}, // SCAL0, 1/8 vertical & horizontal down sampling 409 | {0xA1, 0x80}, // SCAL1, Horizontal Zoom Out Control, set ratio to 1/2 410 | {0xA2, 0x80}, // SCAL2, Vertical Zoom Out Control, set ratio to 1/2 411 | 412 | {OV772x_REG_HSTART, 0x23}, 413 | {OV772x_REG_HSIZE, 0xa0}, // Horizontal Sensor Size: full VGA (no windowing) 414 | {0x29, 0x14}, // Horizontal Data Output Size (80px) MSBs 415 | {OV772x_REG_VSTART, 0x07}, 416 | {OV772x_REG_VSIZE, 0xf0}, // Vertical Sensor Size: full VGA (no windowing) 417 | {0x2c, 0x22}, // Vertical Data Output Size (60px)MSBs 418 | {OV772x_REG_HREF, 0x00}, 419 | {0x2a, 0x00}, // EXHCH 420 | 421 | {0x15,0x01}, // Output data range selection, Data from [10] to [F0] (8 MSBs) 422 | { 0xff, 0xff } // END MARKER 423 | 424 | }; 425 | 426 | 427 | const struct regval_list common_reglist_ov772x[] PROGMEM = 428 | { 429 | 430 | // most of these are color correction stuff 431 | {0x42, 0x7f}, 432 | {0x4d, 0x09}, 433 | {0x63, 0xe0}, // AWB_Ctrl0 434 | {OV772x_REG_COM3, 0x00}, // flip Y with UV 435 | {OV772x_REG_DSP_CTRL1, 0xff}, 436 | {OV772x_REG_DSP_CTRL3, 0x00}, // flip Y with UV 437 | {OV772x_REG_DSP_CTRL4, 0x48}, 438 | {0x13, 0xf0}, 439 | {0x0d, 0x61}, // 51/61/71 for different AEC/AGC window 440 | {0x0f, 0xc5}, 441 | {0x14, 0x11}, 442 | {0x22, 0x7f}, // ff/7f/3f/1f for 60/30/15/7.5fps 443 | {0x23, 0x03}, // 01/03/07/0f for 60/30/15/7.5fps 444 | {0x24, 0x40}, 445 | {0x25, 0x30}, 446 | {0x26, 0xa1}, 447 | {0x2b, 0x00}, // 00/9e for 60/50Hz 448 | {0x6b, 0xaa}, 449 | {0x13, 0xff}, 450 | {0x90, 0x05}, 451 | {0x91, 0x01}, 452 | {0x92, 0x03}, 453 | {0x93, 0x00}, 454 | {0x94, 0xb0}, 455 | {0x95, 0x9d}, 456 | {0x96, 0x13}, 457 | {0x97, 0x16}, 458 | {0x98, 0x7b}, 459 | {0x99, 0x91}, 460 | {0x9a, 0x1e}, 461 | {0x9e, 0x81}, 462 | //{0xa6, 0x03}, // Special Digital Effect Control; luma, contrast, saturation hue 463 | //{0x9b,0x00}, // set luma 464 | //{0x9c,0x25}, // set contrast 465 | //{0xa7,0x65}, // set saturation 466 | //{0xa8,0x65}, // set saturation 467 | //{0xa9,0x80}, // set hue 468 | //{0xaa,0x80}, // set hue 469 | {0x7e, 0x0c}, 470 | {0x7f, 0x16}, 471 | {0x80, 0x2a}, 472 | {0x81, 0x4e}, 473 | {0x82, 0x61}, 474 | {0x83, 0x6f}, 475 | {0x84, 0x7b}, 476 | {0x85, 0x86}, 477 | {0x86, 0x8e}, 478 | {0x87, 0x97}, 479 | {0x88, 0xa4}, 480 | {0x89, 0xaf}, 481 | {0x8a, 0xc5}, 482 | {0x8b, 0xd7}, 483 | {0x8c, 0xe8}, 484 | {0x8d, 0x20}, 485 | {0xff, 0xff} // END MARKER 486 | }; 487 | 488 | 489 | 490 | #endif /* _OV772x_REGS_H */ 491 | 492 | 493 | -------------------------------------------------------------------------------- /arduvision_02_mega/arduino/ov_fifo_test_mega/ov_fifo_test_mega.ino: -------------------------------------------------------------------------------- 1 | /********************************************* 2 | * 3 | * Part of the ARDUVISION project 4 | * 5 | * by David Sanz Kirbis 6 | * 7 | * More info: http://www.arduvision.com 8 | * 9 | * 10 | * 2014 Aug 19 - Mixed some code to be used with an Atmega 328p 11 | * and the Arduino Wire library: 12 | * https://github.com/desaster/sensortest 13 | * http://forum.arduino.cc/index.php?topic=159557 14 | * 15 | * Aug 28 - Added definitions to be able to work with either 16 | * the hardware or the software serial. If using the 17 | * hardware UART, the TX and RX pins have to be 18 | * disconnected from the fifo or ensure they are not 19 | * written while reading the LS data bits. 20 | * - Included PinChangeInt library and change the code 21 | * so we dont wait while the CMOS IC loads the frame 22 | * into the fifo IC (which takes ~33ms at 30fps). 23 | * http://dl.bintray.com/greygnome/generic/pinchangeint-2.30beta.zip 24 | * Initial versions will just overwrite the start 25 | * of the fifo to store each new frame. 26 | * Sep 25 - Cleaned up and reorganized the code for a public release. 27 | * Increased baudrate after modifying arduino's HardwareSerial.cpp 28 | * see http://mekonik.wordpress.com/2009/03/02/modified-arduino-library-serial/ 29 | * 30 | ********************************************/ 31 | 32 | // -------------------------------- 33 | // http://subethasoftware.com/2013/04/09/arduino-compiler-problem-with-ifdefs-solved/ 34 | // BOF preprocessor bug prevent - insert me on top of your arduino-code 35 | // From: http://www.a-control.de/arduino-fehler/?lang=en 36 | #if 1 37 | __asm volatile ("nop"); 38 | #endif 39 | // -------------------------------- 40 | 41 | #include "IO_config.h" 42 | #include "sensor.h" 43 | #include "fifo.h" 44 | #include 45 | 46 | //#define USE_SOFT_SERIAL 47 | // serial stuff 48 | static const byte LF = 10; // line feed character 49 | #ifdef USE_SOFT_SERIAL 50 | #include 51 | static const unsigned int _BAUDRATE = 19200; // 19200 is the maximum reliable soft serial baud rate for 8MHz processors 52 | #define txPin A0 53 | #define rxPin A1 54 | SoftwareSerial mySerial = SoftwareSerial(rxPin, txPin); 55 | SoftwareSerial *serialPtr = &mySerial; 56 | #else 57 | // 38400 is the maximum supposed reliable UART baud rate for 8MHz processors 58 | // However, I've had succes at 500000bps with an USB-FTDI cable 59 | // I've modified the file arduino-1.6.5/hardware/arduino/avr/cores/arduino/HardwareSerial.cpp 60 | // substituting all the lines with operations like this (for both rx and tx buffers): 61 | // 62 | // _rx_buffer_tail = (rx_buffer_index_t)(_rx_buffer_tail + 1) % SERIAL_RX_BUFFER_SIZE; 63 | // 64 | // for two lines like: 65 | // 66 | // _rx_buffer_tail++; 67 | // _rx_buffer_tail %= SERIAL_RX_BUFFER_SIZE; 68 | // 69 | // see http://mekonik.wordpress.com/2009/03/02/modified-arduino-library-serial/ 70 | // 71 | static const unsigned long _BAUDRATE = 500000; 72 | HardwareSerial *serialPtr = &Serial; 73 | #endif 74 | 75 | uint8_t rcvbuf[16], rcvbufpos = 0, c; 76 | 77 | // fps calculation stuff 78 | static unsigned int oneSecond = 1000; 79 | unsigned int volatile frameCount = 0; 80 | unsigned int fps = 0; 81 | unsigned long volatile lastTime = 0; 82 | unsigned long volatile timeStamp = 0; 83 | 84 | //#define QQVGA 85 | #define QQQVGA 86 | 87 | #ifdef QQVGA 88 | static const uint8_t fW = 160; 89 | static const uint8_t fH = 120; 90 | static const frameFormat_t frameFormat = FF_QQVGA; 91 | #else 92 | #ifdef QQQVGA 93 | static const uint8_t fW = 80; 94 | static const uint8_t fH = 60; 95 | static const frameFormat_t frameFormat = FF_QQQVGA; 96 | #endif 97 | #endif 98 | 99 | static const uint8_t TRACK_BORDER = 4; // always multiple of 2 (YUYV: 2 pixels) 100 | static const uint8_t YUYV_BPP = 2; // bytes per pixel 101 | static const unsigned int MAX_FRAME_LEN = fW * YUYV_BPP; 102 | byte rowBuf[MAX_FRAME_LEN]; 103 | unsigned int volatile nRowsSent = 0; 104 | boolean volatile bRequestPending = false; 105 | boolean volatile bNewFrame = false; 106 | uint8_t volatile thresh = 128; 107 | 108 | enum serialRequest_t { 109 | SEND_NONE = 0, 110 | SEND_DARK, 111 | SEND_BRIG, 112 | SEND_FPS, 113 | SEND_0PPB = MAX_FRAME_LEN, 114 | SEND_1PPB = fW, 115 | SEND_2PPB = fW/2, 116 | SEND_4PPB = fW/4, 117 | SEND_8PPB =fW/8 118 | }; 119 | 120 | serialRequest_t serialRequest = SEND_NONE; 121 | 122 | 123 | // ***************************************************** 124 | // SETUP 125 | // ***************************************************** 126 | void setup() 127 | { 128 | setup_IO_ports(); 129 | 130 | serialPtr->begin(_BAUDRATE); 131 | 132 | serialPtr->println("Initializing sensor..."); 133 | for (int i = 0; i < 10; i ++) { 134 | unsigned int result = sensor_init(frameFormat); 135 | if (result != 0) { 136 | serialPtr->print("inited OK, sensor PID: "); 137 | serialPtr->println(result, HEX); 138 | break; 139 | } 140 | else if (i == 5) { 141 | serialPtr->println("PANIC! sensor init keeps failing!"); 142 | while (1); 143 | } else { 144 | serialPtr->println("retrying..."); 145 | delay(300); 146 | } 147 | } 148 | attachInterrupt(VSYNC_INT, (void(*)())&vsyncIntFunc, FALLING); 149 | delay(100); 150 | } 151 | // ***************************************************** 152 | // LOOP 153 | // ***************************************************** 154 | void loop() 155 | { 156 | 157 | 158 | } 159 | 160 | // ***************************************************** 161 | // VSYNC INTERRUPT HANDLER 162 | // ***************************************************** 163 | void __inline__ vsyncIntFunc() { 164 | DISABLE_WREN; // disable writing to fifo 165 | 166 | if (bRequestPending && bNewFrame) { 167 | detachInterrupt(VSYNC_INT); 168 | processRequest(); 169 | bRequestPending = false; 170 | bNewFrame = false; 171 | attachInterrupt(VSYNC_INT, (void(*)())&vsyncIntFunc, FALLING); 172 | } 173 | else { 174 | ENABLE_WRST; 175 | SET_RCLK_H; 176 | SET_RCLK_L; 177 | DISABLE_WRST; 178 | _delay_cycles(10); 179 | 180 | ENABLE_WREN; // enable writing to fifo 181 | bNewFrame = true; 182 | } 183 | } 184 | 185 | // ************************************************************** 186 | // PROCESS SERIAL REQUEST 187 | // ************************************************************** 188 | void processRequest() { 189 | 190 | fifo_rrst(); 191 | 192 | switch (serialRequest) { 193 | case SEND_0PPB: for (int i =0; i< fH; i++) { 194 | fifo_readRow0ppb(rowBuf, rowBuf+serialRequest); 195 | serialPtr->write(rowBuf, serialRequest); 196 | serialPtr->write(LF); 197 | } break; 198 | case SEND_1PPB: for (int i =0; i< fH; i++) { 199 | fifo_readRow1ppb(rowBuf, rowBuf+serialRequest); 200 | serialPtr->write(rowBuf, serialRequest); 201 | serialPtr->write(LF); 202 | } break; 203 | case SEND_2PPB: for (int i =0; i< fH; i++) { 204 | fifo_readRow2ppb(rowBuf, rowBuf+serialRequest); 205 | serialPtr->write(rowBuf, serialRequest); 206 | serialPtr->write(LF); 207 | } break; 208 | case SEND_4PPB: for (int i =0; i< fH; i++) { 209 | fifo_readRow4ppb(rowBuf, rowBuf+serialRequest); 210 | serialPtr->write(rowBuf, serialRequest); 211 | serialPtr->write(LF); 212 | } break; 213 | case SEND_8PPB: for (int i =0; i< fH; i++) { 214 | fifo_readRow8ppb(rowBuf, rowBuf+serialRequest, thresh); 215 | serialPtr->write(rowBuf, serialRequest); 216 | serialPtr->write(LF); 217 | } break; 218 | case SEND_BRIG: fifo_getBrig(rowBuf, fW, fH, TRACK_BORDER, thresh); 219 | serialPtr->write(rowBuf, 4); 220 | serialPtr->write(LF); 221 | break; 222 | case SEND_DARK: fifo_getDark(rowBuf, fW, fH, TRACK_BORDER, thresh); 223 | serialPtr->write(rowBuf, 4); 224 | serialPtr->write(LF); 225 | break; 226 | case SEND_FPS: calcFPS(fps); 227 | serialPtr->print(fps, DEC); 228 | serialPtr->write(LF); 229 | break; 230 | 231 | default : break; 232 | } 233 | } 234 | 235 | 236 | // ************************************************************** 237 | // CALCULATE FPS 238 | // ************************************************************** 239 | void calcFPS(unsigned int ¤tFPS) { 240 | unsigned long currTime = millis(); 241 | unsigned long currTimeDiff = currTime-lastTime; 242 | if (currTimeDiff >= oneSecond) { 243 | lastTime = currTime; 244 | currentFPS = (oneSecond*frameCount)/currTimeDiff; 245 | frameCount = 0; 246 | 247 | } 248 | while (GET_VSYNC); // wait for an old frame to end 249 | while (!GET_VSYNC);// wait for a new frame to start 250 | frameCount++; 251 | } 252 | // ************************************************************** 253 | // SERIAL EVENT 254 | // ************************************************************** 255 | 256 | void serialEvent() { 257 | while (serialPtr->available()) { 258 | // get the new byte: 259 | c = serialPtr->read(); 260 | if (c != LF) { 261 | rcvbuf[rcvbufpos++] = c; 262 | } else if (c == LF) { 263 | rcvbuf[rcvbufpos++] = 0; 264 | rcvbufpos = 0; 265 | parseSerialBuffer(); 266 | } 267 | } 268 | } 269 | 270 | // ***************************************************** 271 | // PARSE SERIAL BUFFER 272 | // **************************************************** 273 | void parseSerialBuffer(void) { 274 | if (strcmp((char *) rcvbuf, "hello") == 0) { 275 | serialPtr->print("Hello to you too!\n"); 276 | } else if ( strlen((char *) rcvbuf) > 5 && 277 | strncmp((char *) rcvbuf, "send ", 5) == 0) { 278 | serialRequest = (serialRequest_t)atoi((char *) (rcvbuf + 5)); 279 | serialPtr->print("ACK\n"); 280 | bRequestPending = true; 281 | } 282 | else if (strlen((char *) rcvbuf) > 5 && 283 | strncmp((char *) rcvbuf, "dark ", 5) == 0) { 284 | thresh = atoi((char *) (rcvbuf + 5)); 285 | serialPtr->print("ACK\n"); 286 | serialRequest = SEND_DARK; 287 | bRequestPending = true; 288 | } 289 | else if (strlen((char *) rcvbuf) > 5 && 290 | strncmp((char *) rcvbuf, "brig ", 5) == 0) { 291 | thresh = atoi((char *) (rcvbuf + 5)); 292 | serialPtr->print("ACK\n"); 293 | serialRequest = SEND_BRIG; 294 | bRequestPending = true; 295 | } 296 | else if (strlen((char *) rcvbuf) > 7 && 297 | strncmp((char *) rcvbuf, "thresh ", 7) == 0) { 298 | thresh = atoi((char *) (rcvbuf + 7)); 299 | } 300 | } 301 | 302 | -------------------------------------------------------------------------------- /arduvision_02_mega/arduino/ov_fifo_test_mega/sensor.cpp: -------------------------------------------------------------------------------- 1 | 2 | //************************** 3 | 4 | 5 | //************************** 6 | 7 | 8 | #include "sensor.h" 9 | #include "ov772x_regs.h" 10 | #include "ov7670_regs.h" 11 | 12 | 13 | #include 14 | 15 | #include "delay.h" 16 | 17 | uint16_t sensor_init(frameFormat_t fFormat) 18 | { 19 | regval_list *format_reglist, *common_reglist; 20 | uint8_t resetReg, resetCommand; 21 | 22 | Wire.begin(); 23 | 24 | _delayMilliseconds(5); 25 | 26 | uint16_t productID = sensor_readReg(REG_PID); 27 | switch(productID) { 28 | case 0x76: //ov7670 29 | productID <<= 8; 30 | productID |= sensor_readReg(REG_VER); 31 | switch (fFormat) { 32 | default: 33 | case FF_QQVGA: format_reglist = (regval_list*)qqvga_yuv_ov7670; break; 34 | case FF_QQQVGA: format_reglist = (regval_list*)qqqvga_yuv_ov7670; break; 35 | } 36 | common_reglist = (regval_list*)common_reglist_ov7670; 37 | resetReg = 0x12; 38 | resetCommand = 0x80; 39 | break; 40 | case 0x77: //ov772x 41 | productID <<= 8; 42 | productID |= sensor_readReg(REG_VER); 43 | switch (fFormat) { 44 | default: 45 | case FF_QQVGA: format_reglist = (regval_list*)qqvga_yuv_ov772x; break; 46 | case FF_QQQVGA: format_reglist = (regval_list*)qqqvga_yuv_ov772x; break; 47 | } 48 | common_reglist = (regval_list*)common_reglist_ov772x; 49 | resetReg = 0x12; 50 | resetCommand = 0x80; 51 | break; 52 | default: return 0; 53 | break; 54 | } 55 | 56 | sensor_writeReg(resetReg, resetCommand); // reset to default values 57 | delay(300); // Setting time for register change 58 | sensor_writeRegs(common_reglist); 59 | delay(300); // Setting time for register change 60 | sensor_writeRegs(format_reglist); 61 | delay(300); // Setting time for register change 62 | return productID; 63 | } 64 | //************************** 65 | // Write byte value regDat to the camera register addressed by regID 66 | uint8_t sensor_writeReg(uint8_t regID, uint8_t regDat) { 67 | Wire.beginTransmission(OV772x_WR_ADDR >> 1); 68 | Wire.write(regID & 0x00FF); 69 | Wire.write(regDat & 0x00FF); 70 | uint8_t result = Wire.endTransmission(); 71 | //delay(1); 72 | return result; 73 | } 74 | //************************** 75 | void sensor_writeRegs(const regval_list reglist[]) { 76 | uint8_t reg_addr; 77 | uint8_t reg_val; 78 | const struct regval_list *next = reglist; 79 | while ((reg_addr != 0xFF) | (reg_val != 0xFF)){ 80 | reg_addr = pgm_read_byte(&next->reg_num); 81 | reg_val = pgm_read_byte(&next->value); 82 | sensor_writeReg(reg_addr, reg_val); 83 | next++; 84 | } 85 | } 86 | //************************** 87 | // Read a byte value from the camera addressed at regID, and store it at 88 | // memory location pointed to by regDat. Return 1 on success, 0 on failure. 89 | uint8_t sensor_readReg(uint8_t regID) { 90 | uint8_t regDat; 91 | Wire.beginTransmission(OV772x_RD_ADDR >> 1); 92 | Wire.write(regID & 0x00FF); 93 | Wire.endTransmission(); 94 | Wire.requestFrom((OV772x_RD_ADDR >> 1),1); 95 | if(Wire.available()) { 96 | regDat = Wire.read(); 97 | //delay(1); 98 | return regDat; 99 | } else { 100 | return 0; 101 | } 102 | } 103 | 104 | //************************** 105 | void sensor_printlnRegs(const regval_list reglist[], Stream &destPort) { 106 | uint8_t reg_addr; 107 | uint8_t reg_val; 108 | uint8_t regRead_val; 109 | 110 | const struct regval_list *next = reglist; 111 | while ((reg_addr != 0xFF) | (reg_val != 0xFF)){ 112 | reg_addr = pgm_read_byte(&next->reg_num); 113 | reg_val = pgm_read_byte(&next->value); 114 | regRead_val = sensor_readReg(reg_addr); 115 | next++; 116 | destPort.print("{"); 117 | destPort.print(reg_addr, HEX); 118 | destPort.print(", "); 119 | destPort.print(regRead_val, HEX); 120 | destPort.println("},"); 121 | 122 | } 123 | } 124 | 125 | 126 | 127 | -------------------------------------------------------------------------------- /arduvision_02_mega/arduino/ov_fifo_test_mega/sensor.h: -------------------------------------------------------------------------------- 1 | #ifndef _SENSOR_H 2 | #define _SENSOR_H 3 | 4 | 5 | #include 6 | 7 | 8 | #include "delay.h" 9 | #define REG_PID 0x0a // Product ID MSB 10 | #define REG_VER 0x0b // Product ID LSB 11 | 12 | struct regval_list { 13 | uint8_t reg_num; 14 | uint8_t value; 15 | }; 16 | enum frameFormat_t { 17 | FF_QQVGA, 18 | FF_QQQVGA 19 | }; 20 | 21 | 22 | uint16_t sensor_init(frameFormat_t fFormat); 23 | void al422_loadFrame(void); 24 | uint8_t sensor_writeReg(uint8_t regID, uint8_t regDat); 25 | void sensor_writeRegs(const regval_list reglist[]); 26 | uint8_t sensor_readReg(uint8_t regID); 27 | void sensor_printlnRegs(const regval_list reglist[]); 28 | void wait(void); 29 | 30 | #endif /* _SENSOR_H */ 31 | -------------------------------------------------------------------------------- /arduvision_02_mega/docs/arduvision_ov7670_fino_mega.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/dasaki/arduvision/950bd8788613f60f09086abd510b397fe3b9d73e/arduvision_02_mega/docs/arduvision_ov7670_fino_mega.png -------------------------------------------------------------------------------- /arduvision_02_mega/processing/receive_stream_mega/globalDefinitions.java: -------------------------------------------------------------------------------- 1 | 2 | final class G_DEF { 3 | public final static int BAUDRATE = 500000; 4 | 5 | public final static char LF = '\n'; // Linefeed in ASCII 6 | public final static char CR = '\r'; // Carriage return in ASCII 7 | 8 | public final static int SCR_W = 640; 9 | public final static int SCR_H = 480; 10 | public final static int F_W = 80; 11 | public final static int F_H = 60; 12 | public final static int BPP = 2; 13 | public final static int FONT_SIZE = 18; 14 | public final static int FONT_BKG_SIZE = (int)(FONT_SIZE*(float)1.5); 15 | public final static float DRAW_SCALE = (float)SCR_W / (float)F_W; 16 | 17 | public final static int MAX_ROW_LEN = F_W*BPP; // pixels + LF character 18 | public final static int MAX_ROW_BUFF_LEN = MAX_ROW_LEN+1; // pixels + LF character 19 | public final static int ACK_BUF_LEN = 255; // serial buffer to store "ACK"+LF 20 | public final static long SERIAL_TIMEOUT = 2; // milliseconds to wait for ACK 21 | } 22 | 23 | enum requestStatus_t { 24 | IDLE, REQUESTED, TIMEOUT, ARRIVING, RECEIVED, PROCESSING 25 | }; 26 | 27 | enum request_t { 28 | NONE(0), 29 | TRACKDARK(1), 30 | TRACKBRIG(2), 31 | STREAM8PPB(G_DEF.F_W/8), 32 | STREAM4PPB(G_DEF.F_W/4), 33 | STREAM2PPB(G_DEF.F_W/2), 34 | STREAM1PPB(G_DEF.F_W), 35 | STREAM0PPB(G_DEF.F_W*G_DEF.BPP); 36 | 37 | private int value; 38 | 39 | private request_t(int value) { 40 | this.value = value; 41 | } 42 | 43 | public int getParam() { 44 | return value; 45 | } 46 | }; 47 | 48 | -------------------------------------------------------------------------------- /arduvision_02_mega/processing/receive_stream_mega/receive_stream_mega.pde: -------------------------------------------------------------------------------- 1 | /************************************************************** 2 | * 3 | * Part of the ARDUVISION project 4 | * 5 | * by David Sanz Kirbis 6 | * 7 | * Receive the image and/or tracking data from a CMOS sensor 8 | * controlled by an Arduino board. 9 | * In the arduino side use the example sketch "ov_fifo_test.ino" 10 | * 11 | * More info: http://www.arduvision.com 12 | * 13 | * 14 | * 15 | **************************************************************/ 16 | 17 | 18 | import processing.serial.*; 19 | import java.util.*; 20 | 21 | 22 | 23 | Serial serialPort; 24 | 25 | request_t request; 26 | requestStatus_t reqStatus = requestStatus_t.IDLE; 27 | 28 | // incoming serial 29 | byte[] ackBuff = new byte[G_DEF.ACK_BUF_LEN]; 30 | byte[][] pix = new byte[G_DEF.F_H][G_DEF.MAX_ROW_LEN]; 31 | 32 | double waitTimeout = 0; 33 | double fpsTimeStamp = 0; 34 | 35 | PFont myFont; 36 | PImage currFrame; 37 | 38 | boolean bSerialDebug = true; 39 | 40 | int currRow = 0; 41 | byte thresh = (byte)130; 42 | 43 | PVector lastCenter = new PVector(0,0); 44 | float tmp_x0 = 0, tmp_y0 = 0, tmp_x1 = 0, tmp_y1 = 0; 45 | float x0 = 0, y0 = 0, x1 = 0, y1 = 0; 46 | 47 | boolean bKalmanEnabled = true; 48 | simpleKalman filter_x0 = new simpleKalman(); 49 | simpleKalman filter_y0 = new simpleKalman(); 50 | simpleKalman filter_x1 = new simpleKalman(); 51 | simpleKalman filter_y1 = new simpleKalman(); 52 | 53 | // ************************************************************ 54 | // SETUP 55 | // ************************************************************ 56 | 57 | void setup() { 58 | size(640, 527); 59 | 60 | frameRate(30); 61 | 62 | currFrame = createImage(G_DEF.F_W, G_DEF.F_H, RGB); 63 | 64 | 65 | // create a font with the third font available to the system: 66 | myFont = createFont("Arial", G_DEF.FONT_SIZE); 67 | textFont(myFont); 68 | 69 | // List all the available serial serialPorts: 70 | printArray(Serial.list()); 71 | 72 | delay(500); 73 | serialPort = new Serial(this, "/dev/ttyACM0", G_DEF.BAUDRATE); 74 | serialPort.bufferUntil(G_DEF.LF); 75 | serialPort.clear(); 76 | delay(2000); 77 | reqStatus = reqStatus.IDLE; 78 | request = request.NONE; 79 | } 80 | 81 | // ************************************************************ 82 | // DRAW 83 | // ************************************************************ 84 | void draw() { 85 | switch (request) { 86 | case NONE: reqStatus = requestStatus_t.IDLE; 87 | background(0); 88 | drawInfo(); 89 | break; 90 | case TRACKDARK: 91 | case TRACKBRIG: switch (reqStatus) { 92 | case RECEIVED: drawTracking(); 93 | drawFPS(); 94 | reqStatus = requestStatus_t.IDLE; 95 | break; 96 | case TIMEOUT: 97 | case IDLE: reqTracking(request); 98 | reqStatus = requestStatus_t.REQUESTED; 99 | waitTimeout = G_DEF.SERIAL_TIMEOUT + millis(); 100 | break; 101 | case REQUESTED: if (millis() > waitTimeout) reqStatus = requestStatus_t.TIMEOUT; 102 | break; 103 | case ARRIVING: break; 104 | default : break; 105 | } 106 | drawInfo(); 107 | break; 108 | case STREAM0PPB: 109 | case STREAM1PPB: 110 | case STREAM2PPB: 111 | case STREAM4PPB: 112 | case STREAM8PPB: switch (reqStatus) { 113 | case RECEIVED: reqStatus = requestStatus_t.PROCESSING; 114 | buff2pixFrame(pix, currFrame, request); 115 | noSmooth(); 116 | image(currFrame,0,0, G_DEF.F_W*G_DEF.DRAW_SCALE,G_DEF.F_H*G_DEF.DRAW_SCALE); 117 | smooth(); 118 | drawFPS(); 119 | reqStatus = requestStatus_t.IDLE; 120 | break; 121 | case TIMEOUT: 122 | case IDLE: reqImage(request); 123 | reqStatus = requestStatus_t.REQUESTED; 124 | waitTimeout = G_DEF.SERIAL_TIMEOUT + millis(); 125 | break; 126 | case REQUESTED: if (millis() > waitTimeout) reqStatus = requestStatus_t.TIMEOUT; 127 | break; 128 | case ARRIVING: break; 129 | case PROCESSING: break; 130 | default : break; 131 | } 132 | drawInfo(); 133 | break; 134 | default : break; 135 | } 136 | } 137 | 138 | // ************************************************************ 139 | // SERIAL EVENT HANDLER 140 | // ************************************************************ 141 | void serialEvent(Serial serialPort) { 142 | 143 | if (reqStatus == requestStatus_t.REQUESTED) { 144 | int numBytesRead = serialPort.readBytesUntil(G_DEF.LF, ackBuff); 145 | if ((numBytesRead >= 4) && 146 | (ackBuff[numBytesRead-4] == 'A') && 147 | (ackBuff[numBytesRead-3] == 'C') && 148 | (ackBuff[numBytesRead-2] == 'K') ) { 149 | reqStatus = requestStatus_t.ARRIVING; 150 | } else if (millis() > waitTimeout) { 151 | reqStatus = requestStatus_t.TIMEOUT; 152 | } 153 | } 154 | else if (reqStatus == requestStatus_t.ARRIVING) { 155 | parseSerialData(); 156 | } 157 | else { 158 | if (bSerialDebug) print(serialPort.readStringUntil(G_DEF.LF)); 159 | } 160 | } 161 | 162 | // ************************************************************ 163 | // PARSE SERIAL DATA 164 | // ************************************************************ 165 | void parseSerialData() { 166 | switch (request) { 167 | case NONE: break; 168 | case TRACKDARK: 169 | case TRACKBRIG: tmp_x0 = int(serialPort.read()); 170 | tmp_y0 = int(serialPort.read()); 171 | tmp_x1 = int(serialPort.read()); 172 | tmp_y1 = int(serialPort.read()); 173 | reqStatus = requestStatus_t.RECEIVED; 174 | break; 175 | case STREAM0PPB: 176 | case STREAM1PPB: 177 | case STREAM2PPB: 178 | case STREAM4PPB: 179 | case STREAM8PPB: serialPort.readBytes(pix[currRow]); 180 | serialPort.clear(); 181 | currRow++; 182 | if (currRow >= G_DEF.F_H) { 183 | reqStatus = requestStatus_t.RECEIVED; // frame ready on buffer 184 | currRow = 0; 185 | if (bSerialDebug) println(); 186 | } 187 | break; 188 | default : break; 189 | } 190 | 191 | } 192 | 193 | // ************************************************************ 194 | // REQUEST IMAGE 195 | // ************************************************************ 196 | void reqImage(request_t req) { 197 | currRow = 0; 198 | serialPort.clear(); 199 | serialPort.write("thresh "+Integer.toString(int(thresh))+G_DEF.LF); 200 | serialPort.write("send "+Integer.toString(req.getParam())+G_DEF.LF); 201 | } 202 | 203 | // ************************************************************ 204 | // REQUEST TRACKING DATA 205 | // ************************************************************ 206 | void reqTracking(request_t req) { 207 | 208 | serialPort.clear(); 209 | if (req == request_t.TRACKDARK) 210 | serialPort.write("dark "+Integer.toString(int(thresh))+G_DEF.LF); 211 | else if (req == request_t.TRACKBRIG) 212 | serialPort.write("brig "+Integer.toString(int(thresh))+G_DEF.LF); 213 | 214 | } 215 | 216 | // ************************************************************ 217 | // DRAW SCREEN INFO 218 | // ************************************************************ 219 | void drawInfo() { 220 | String modeStr = "Press space to toggle MODE: "+request; 221 | pushStyle(); 222 | pushMatrix(); 223 | noStroke(); 224 | fill(64); 225 | rect(0, height-G_DEF.FONT_BKG_SIZE, width, G_DEF.FONT_BKG_SIZE); 226 | fill(255); 227 | textAlign(LEFT, TOP); 228 | text(modeStr, 20, height-G_DEF.FONT_BKG_SIZE); 229 | textAlign(RIGHT, TOP); 230 | text("thresh (+/-): "+int(thresh), width-20, height-G_DEF.FONT_BKG_SIZE); 231 | popMatrix(); 232 | popStyle(); 233 | } 234 | 235 | // ************************************************************ 236 | // DRAW FPS 237 | // ************************************************************ 238 | void drawFPS() { 239 | long currTime = millis(); 240 | float fps =1000.0/(float)(currTime-fpsTimeStamp); 241 | 242 | pushStyle(); 243 | pushMatrix(); 244 | noStroke(); 245 | fill(0); 246 | rect(20, 20, textWidth("FPS: "+fps), G_DEF.FONT_SIZE); 247 | fill(255); 248 | translate(0,-2); 249 | textAlign(LEFT, TOP); 250 | text("FPS: "+fps, 20, 20); 251 | popMatrix(); 252 | popStyle(); 253 | fpsTimeStamp = currTime; 254 | } 255 | 256 | // ************************************************************ 257 | // DRAW TRACKING 258 | // ************************************************************ 259 | void drawTracking() { 260 | pushStyle(); 261 | noFill(); 262 | strokeWeight(3); 263 | 264 | if (tmp_x1-tmp_x0 > 3 && tmp_x1-tmp_x0 < G_DEF.F_W/2 && tmp_y1-tmp_y0 < G_DEF.F_H/2 && tmp_y1-tmp_y0 > 3) { 265 | stroke(0); 266 | float minX = width-x0*G_DEF.DRAW_SCALE; 267 | float minY = y0*G_DEF.DRAW_SCALE; 268 | float wX = -(x1-x0)*G_DEF.DRAW_SCALE; 269 | float hY = (y1-y0)*G_DEF.DRAW_SCALE; 270 | float centX = minX+wX/2; 271 | float centY = minY+hY/2; 272 | rect(minX, minY, wX, hY ); 273 | line( centX-10, centY, centX+10, centY ); 274 | line( centX, centY-10, centX, centY+10 ); 275 | if (bKalmanEnabled) { 276 | x0 = (float)filter_x0.update(tmp_x0); 277 | y0 = (float)filter_y0.update(tmp_y0); 278 | x1 = (float)filter_x1.update(tmp_x1); 279 | y1 = (float)filter_y1.update(tmp_y1); 280 | } 281 | else { 282 | x0 = tmp_x0; 283 | y0 = tmp_y0; 284 | x1 = tmp_x1; 285 | y1 = tmp_y1; 286 | } 287 | stroke(255,0,0); 288 | minX = width-x0*G_DEF.DRAW_SCALE; 289 | minY = y0*G_DEF.DRAW_SCALE; 290 | wX = -(x1-x0)*G_DEF.DRAW_SCALE; 291 | hY = (y1-y0)*G_DEF.DRAW_SCALE; 292 | centX = minX+wX/2; 293 | centY = minY+hY/2; 294 | 295 | rect(minX, minY, wX, hY ); 296 | 297 | 298 | line( centX-10, centY, centX+10, centY ); 299 | line( centX, centY-10, centX, centY+10 ); 300 | stroke(0,0,255); 301 | line(lastCenter.x, lastCenter.y,centX, centY); 302 | lastCenter.x = centX; 303 | lastCenter.y = centY; 304 | 305 | } 306 | popStyle(); 307 | } 308 | 309 | // ************************************************************ 310 | // CONVERT PIXEL STREAM BUFFER TO PIMAGE 311 | // ************************************************************ 312 | void buff2pixFrame(byte[][] pixBuff, PImage dstImg, request_t req) { 313 | 314 | int Y0 = 0, U = 0, Y1 = 0, V = 0; 315 | int Y2 = 0, Y3 = 0, Y4 = 0; 316 | int reqParam = req.getParam(); 317 | 318 | dstImg.loadPixels(); 319 | 320 | switch (req) { 321 | case STREAM0PPB: for (int y = 0, l = 0, x = 0; y < G_DEF.F_H; y++, x = 0) 322 | while (x < reqParam) { 323 | Y0 = int(pixBuff[y][x++]); 324 | U = int(pixBuff[y][x++]); 325 | Y1 = int(pixBuff[y][x++]); 326 | V = int(pixBuff[y][x++]); 327 | dstImg.pixels[l++] = YUV2RGB(Y0,U,V); 328 | dstImg.pixels[l++] = YUV2RGB(Y1,U,V); 329 | } 330 | break; 331 | case STREAM1PPB: for (int y = 0, l = 0, x = 0; y < G_DEF.F_H; y++, x = 0) 332 | while (x < reqParam) { 333 | Y0 = 0x08 | ((0x0f & int(pixBuff[y][x])) << 4); 334 | U = 0x00 | ((0xf0 & int(pixBuff[y][x++]))); 335 | Y1 = 0x08 | ((0x0f & int(pixBuff[y][x])) << 4); 336 | V = 0x00 | ((0xf0 & int(pixBuff[y][x++]))); 337 | dstImg.pixels[l++] = YUV2RGB(Y0,U,V); 338 | dstImg.pixels[l++] = YUV2RGB(Y1,U,V); 339 | } 340 | break; 341 | case STREAM2PPB: for (int y = 0, l = 0, x = 0; y < G_DEF.F_H; y++, x = 0) 342 | while (x < reqParam) { 343 | Y1 = int(pixBuff[y][x++]); 344 | Y0 = ((Y1 << 4) & 0xF0) | 0x1f; 345 | Y1 = (Y1 & 0xF0) | 0x1f; 346 | dstImg.pixels[l++] = color(Y0); 347 | dstImg.pixels[l++] = color(Y1); 348 | } 349 | break; 350 | case STREAM4PPB: for (int y = 0, l = 0, x = 0; y < G_DEF.F_H; y++, x = 0) 351 | while (x < reqParam) { 352 | Y3 = int(pixBuff[y][x++]); 353 | Y0 = ((Y3 << 6) & 0xC0) | 0x1f; 354 | Y1 = ((Y3 << 4) & 0xC0) | 0x1f; 355 | Y2 = ((Y3 << 2) & 0xC0) | 0x1f; 356 | Y3 = (Y3 & 0xC0) | 0x1f; 357 | dstImg.pixels[l++] = color(Y0); 358 | dstImg.pixels[l++] = color(Y1); 359 | dstImg.pixels[l++] = color(Y2); 360 | dstImg.pixels[l++] = color(Y3); 361 | } 362 | break; 363 | case STREAM8PPB: for (int y = 0, l = 0, x = 0; y < G_DEF.F_H; y++, x = 0) 364 | while (x < reqParam) { 365 | Y0 = int(pixBuff[y][x++]); 366 | 367 | dstImg.pixels[l++] = ((Y0 & 0x01) == 0? 0:0xffffff); 368 | dstImg.pixels[l++] = ((Y0 & 0x02) == 0? 0:0xffffff); 369 | dstImg.pixels[l++] = ((Y0 & 0x04) == 0? 0:0xffffff); 370 | dstImg.pixels[l++] = ((Y0 & 0x05) == 0? 0:0xffffff); 371 | dstImg.pixels[l++] = ((Y0 & 0x10) == 0? 0:0xffffff); 372 | dstImg.pixels[l++] = ((Y0 & 0x20) == 0? 0:0xffffff); 373 | dstImg.pixels[l++] = ((Y0 & 0x40) == 0? 0:0xffffff); 374 | dstImg.pixels[l++] = ((Y0 & 0x80) == 0? 0:0xffffff); 375 | } 376 | break; 377 | } 378 | dstImg.updatePixels(); 379 | } 380 | 381 | // ************************************************************ 382 | // YUV TO RGB 383 | // ************************************************************ 384 | 385 | color YUV2RGB(int Y, int Cb, int Cr) { 386 | // from OV7670 Software Application note 387 | float R = Y + 1.371*(Cr-128); 388 | float G = Y - 0.698*(Cr-128)+0.336*(Cb-128); 389 | float B = Y + 1.732*(Cb-128); 390 | 391 | return color(R, G, B); 392 | } 393 | 394 | // ************************************************************ 395 | // RGB TO YUV 396 | // ************************************************************ 397 | 398 | color RGB2YUV(int R, int G, int B) { 399 | // from OV7670 Software Application note 400 | float Yu = 0.299*R+0.587*G+0.114*B; 401 | float Cb = 0.568*(B-Y)+128; 402 | float Cr = 0.713*(R-Y)+128; 403 | 404 | return color(Yu, Cb, Cr); 405 | } 406 | // ************************************************************ 407 | // 408 | // ************************************************************ 409 | void keyPressed() { 410 | 411 | switch (key) { 412 | case ' ': int i = request.ordinal()+1; 413 | if (i >= request_t.values().length) i=0; 414 | request = request_t.values()[i]; 415 | serialPort.clear(); 416 | reqStatus = requestStatus_t.IDLE; 417 | 418 | break; 419 | case 'k': bKalmanEnabled = !bKalmanEnabled; 420 | break; 421 | case '+': thresh++; 422 | break; 423 | case '-': thresh--; 424 | break; 425 | case 's': saveFrame(); break; 426 | default: break; 427 | } 428 | 429 | } 430 | // ************************************************************ 431 | // 432 | // ************************************************************ 433 | 434 | void mousePressed() { 435 | println(mouseY); 436 | } -------------------------------------------------------------------------------- /arduvision_02_mega/processing/receive_stream_mega/simpleKalman.java: -------------------------------------------------------------------------------- 1 | //---------------- 2 | // adapted from code found here: 3 | // http://trandi.wordpress.com/2011/05/16/kalman-filter-simplified-version/ 4 | // 5 | public class simpleKalman { 6 | private double Q = 0.0001; 7 | private double R = 0.00025; 8 | private double P = 1, X = 0, K; 9 | 10 | private void measurementUpdate(){ 11 | K = (P + Q) / (P + Q + R); 12 | P = R * (P + Q) / (R + P + Q); 13 | } 14 | 15 | public double update(double measurement){ 16 | measurementUpdate(); 17 | double result = X + (measurement - X) * K; 18 | X = result; 19 | 20 | return result; 21 | } 22 | } 23 | //--------------- 24 | 25 | --------------------------------------------------------------------------------