From 0d81e6df4b19f1c22e50ebc4b77c2abc3ed37ed5 Mon Sep 17 00:00:00 2001 From: CuriosMind Date: Fri, 4 Apr 2025 23:16:16 +0200 Subject: [PATCH] =?UTF-8?q?(=E2=95=AF=C2=B0=E2=96=A1=C2=B0)=E2=95=AF?= =?UTF-8?q?=EF=B8=B5=20=E2=94=BB=E2=94=81=E2=94=BB?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .idea/workspace.xml | 168 ++++++++++++++++++++ CMakeLists.txt | 6 +- bus_scan.c | 48 +++--- image.pio | 21 +++ image_receiver.py | 314 ++++++++++++++++++++++++++++++++++++++ src/PicoIris.cpp | 59 ++++--- src/ov2640/SCCB.cpp | 4 +- src/ov2640/camera.cpp | 261 +++++++++++++++---------------- src/pio/image/image.pio.h | 64 -------- src/rp2040/SCCB.cpp | 105 +++++++++++++ src/rp2040/SCCB.hpp | 30 ++++ src/rp2040/ov2640.cpp | 140 +++++++++++++++++ src/rp2040/ov2640.hpp | 36 +++++ src/rp2040/ov2640_init.h | 265 ++++++++++++++++++++++++++++++++ 14 files changed, 1274 insertions(+), 247 deletions(-) create mode 100644 .idea/workspace.xml create mode 100644 image.pio create mode 100644 image_receiver.py delete mode 100644 src/pio/image/image.pio.h create mode 100644 src/rp2040/SCCB.cpp create mode 100644 src/rp2040/SCCB.hpp create mode 100644 src/rp2040/ov2640.cpp create mode 100644 src/rp2040/ov2640.hpp create mode 100644 src/rp2040/ov2640_init.h diff --git a/.idea/workspace.xml b/.idea/workspace.xml new file mode 100644 index 0000000..9d357ca --- /dev/null +++ b/.idea/workspace.xml @@ -0,0 +1,168 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1743341850127 + + + + + + + + + \ No newline at end of file diff --git a/CMakeLists.txt b/CMakeLists.txt index efdad1b..797449b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -35,14 +35,16 @@ pico_sdk_init() # Add executable. Default name is the project name, version 0.1 -add_executable(PicoIris src/PicoIris.cpp src/ov2640/camera.cpp src/ov2640/SCCB.cpp src/pio/i2c/pio_i2c.c) +#add_executable(PicoIris src/PicoIris.cpp src/ov2640/camera.cpp src/ov2640/SCCB.cpp src/pio/i2c/pio_i2c.c) + +add_executable(PicoIris src/PicoIris.cpp src/rp2040/ov2640.cpp src/rp2040/SCCB.cpp src/pio/i2c/pio_i2c.c) #add_executable(PicoIris bus_scan.c) pico_set_program_name(PicoIris "PicoIris") pico_set_program_version(PicoIris "0.1") # Generate PIO header -pico_generate_pio_header(PicoIris ${CMAKE_CURRENT_LIST_DIR}/src/pio/i2c/i2c.pio) +pico_generate_pio_header(PicoIris ${CMAKE_CURRENT_LIST_DIR}/image.pio ${CMAKE_CURRENT_LIST_DIR}/src/pio/i2c/i2c.pio) # Modify the below lines to enable/disable output over UART/USB pico_enable_stdio_uart(PicoIris 0) diff --git a/bus_scan.c b/bus_scan.c index f54b19d..37a6fbf 100644 --- a/bus_scan.c +++ b/bus_scan.c @@ -63,30 +63,34 @@ int main() { // Make the I2C pins available to picotool bi_decl(bi_2pins_with_func(PICO_DEFAULT_I2C_SDA_PIN, PICO_DEFAULT_I2C_SCL_PIN, GPIO_FUNC_I2C)); - printf("\nI2C Bus Scan\n"); - printf(" 0 1 2 3 4 5 6 7 8 9 A B C D E F\n"); - - for (int addr = 0; addr < (1 << 7); ++addr) { - if (addr % 16 == 0) { - printf("%02x ", addr); + while(true){ + printf("\nI2C Bus Scan\n"); + printf(" 0 1 2 3 4 5 6 7 8 9 A B C D E F\n"); + + for (int addr = 0; addr < (1 << 7); ++addr) { + if (addr % 16 == 0) { + printf("%02x ", addr); + } + + // Perform a 1-byte dummy read from the probe address. If a slave + // acknowledges this address, the function returns the number of bytes + // transferred. If the address byte is ignored, the function returns + // -1. + + // Skip over any reserved addresses. + int ret; + uint8_t rxdata; + if (reserved_addr(addr)) + ret = PICO_ERROR_GENERIC; + else + ret = i2c_read_blocking(i2c_default, addr, &rxdata, 1, false); + + printf(ret < 0 ? "." : "@"); + printf(addr % 16 == 15 ? "\n" : " "); } - - // Perform a 1-byte dummy read from the probe address. If a slave - // acknowledges this address, the function returns the number of bytes - // transferred. If the address byte is ignored, the function returns - // -1. - - // Skip over any reserved addresses. - int ret; - uint8_t rxdata; - if (reserved_addr(addr)) - ret = PICO_ERROR_GENERIC; - else - ret = i2c_read_blocking(i2c_default, addr, &rxdata, 1, false); - - printf(ret < 0 ? "." : "@"); - printf(addr % 16 == 15 ? "\n" : " "); + sleep_ms(1000); } + printf("Done.\n"); return 0; #endif diff --git a/image.pio b/image.pio new file mode 100644 index 0000000..97ecd74 --- /dev/null +++ b/image.pio @@ -0,0 +1,21 @@ +.program image +.wrap_target + wait 1 pin 9 // wait for hsync + wait 1 pin 8 // wait for rising pclk + in pins 8 + wait 0 pin 8 +.wrap + +% c-sdk { +void image_program_init(PIO pio, uint sm, uint offset, uint pin_base) { + pio_sm_set_consecutive_pindirs(pio, sm, pin_base, 10, false); + + pio_sm_config c = image_program_get_default_config(offset); + sm_config_set_in_pins(&c, pin_base); + sm_config_set_in_shift(&c, false, true, 8); + sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_RX); + + pio_sm_init(pio, sm, offset, &c); + pio_sm_set_enabled(pio, sm, true); +} +%} \ No newline at end of file diff --git a/image_receiver.py b/image_receiver.py new file mode 100644 index 0000000..41d6611 --- /dev/null +++ b/image_receiver.py @@ -0,0 +1,314 @@ +import serial +import struct +import numpy as np +import os +import binascii +import time +import cv2 # Added OpenCV for image processing + +# Configure serial port - this will connect to the USB serial port from the Pico +PORT = '/dev/tty.usbmodem101' # Adjust for your system +BAUD_RATE = 3000 # Reduced to match the Pico's baud rate for debugging +TIMEOUT = 60 # Increased timeout for slower data transfer + +# Enable detailed debugging information +DEBUG_MODE = True # Set to True for verbose output, False for normal operation + +# Frame constants - match the values in the C++ code +FRAME_HEADER = b'\xDE\xAD\xBE\xEF' # Distinctive header +FRAME_FOOTER = b'\xCA\xFE\xBA\xBE' # Distinctive footer +BINARY_START_MARKER = "BINARY_START" +BINARY_END_MARKER = "###BINARY_END###" # Updated to match the new format + +# Directory to save the frames +output_dir = "frames" +os.makedirs(output_dir, exist_ok=True) + +def debug_hex(data): + """Print data in hexadecimal format for debugging.""" + return binascii.hexlify(data).decode('ascii') + +def save_as_image(frame_data, filename_base, frame_size=(160, 120)): + """Save the frame data as both PNG and raw file formats.""" + try: + # Convert the raw data to a numpy array + img_array = np.frombuffer(frame_data, dtype=np.uint16) + + # Reshape to the expected dimensions + width, height = frame_size + img_array = img_array.reshape(height, width) + + # Convert from RGB565 to BGR format that OpenCV uses + # This conversion depends on your exact pixel format + # RGB565: 5 bits red, 6 bits green, 5 bits blue + img_rgb = np.zeros((height, width, 3), dtype=np.uint8) + + # Extract R, G, B components from RGB565 + r = ((img_array & 0xF800) >> 11) * 8 # 5 bits for red (0-31) scaled to 0-255 + g = ((img_array & 0x07E0) >> 5) * 4 # 6 bits for green (0-63) scaled to 0-255 + b = (img_array & 0x001F) * 8 # 5 bits for blue (0-31) scaled to 0-255 + + img_rgb[:,:,0] = b # OpenCV uses BGR order + img_rgb[:,:,1] = g + img_rgb[:,:,2] = r + + # Save as PNG + png_filename = f"{filename_base}.png" + cv2.imwrite(png_filename, img_rgb) + print(f"Saved PNG image: {png_filename}") + + # Save as JPG with 90% quality + jpg_filename = f"{filename_base}.jpg" + cv2.imwrite(jpg_filename, img_rgb, [cv2.IMWRITE_JPEG_QUALITY, 90]) + print(f"Saved JPG image: {jpg_filename}") + + # Also save the raw numpy array for further analysis if needed + np_filename = f"{filename_base}.npy" + np.save(np_filename, img_array) + print(f"Saved NumPy array: {np_filename}") + + # Save raw binary data too + raw_filename = f"{filename_base}.raw" + with open(raw_filename, "wb") as f: + f.write(frame_data) + print(f"Saved raw data: {raw_filename}") + + return True + + except Exception as e: + print(f"Error saving image: {e}") + import traceback + traceback.print_exc() + return False + +def receive_frame(): + """Receive a complete frame from the serial port.""" + try: + with serial.Serial(PORT, BAUD_RATE, timeout=TIMEOUT) as ser: + print(f"Monitoring serial port: {ser.name}") + + line = "" + in_binary_section = False + binary_data = bytearray() + + # Safety check - maximum buffer size to prevent infinite collection + MAX_BUFFER_SIZE = 500000 # 500KB should be more than enough for a 160x120 frame + + while True: + # Read data from serial port + if ser.in_waiting > 0: + # Try to read a line first to check for markers + c = ser.read(1) + + # If in binary section, collect binary data + if in_binary_section: + binary_data.append(c[0]) + + # Safety check - if buffer gets too large, abort + if len(binary_data) > MAX_BUFFER_SIZE: + print(f"WARNING: Binary data exceeded maximum buffer size ({MAX_BUFFER_SIZE})") + print("Aborting binary collection to prevent memory issues") + return None + + # Show progress for large binary sections + if len(binary_data) % 1000 == 0: + print(f"Collected {len(binary_data)} bytes of binary data") + + # Check if we've accumulated enough data to check for the end marker + # Add the character to our text buffer as well for end marker detection + if c.isascii() and not c.isspace(): + line += c.decode('ascii', errors='replace') + else: + # For whitespace characters, we need special handling + if c == b'\n': + # If the current line contains our end marker + if BINARY_END_MARKER in line: + print(f"Binary end marker detected in line: {line}") + in_binary_section = False + print(f"Total binary data collected: {len(binary_data)} bytes") + + # Print binary data summary + print("First 32 bytes:", debug_hex(binary_data[:32])) + print("Last 32 bytes:", debug_hex(binary_data[-32:])) + + # Find the last occurrence of FRAME_FOOTER + footer_pos = -1 + for i in range(len(binary_data) - len(FRAME_FOOTER)): + if binary_data[i:i+len(FRAME_FOOTER)] == FRAME_FOOTER: + footer_pos = i + + if footer_pos >= 0: + print(f"Frame footer found at position {footer_pos}: {debug_hex(FRAME_FOOTER)}") + # Trim the binary data to end at the footer + footer length + binary_data = binary_data[:footer_pos + len(FRAME_FOOTER)] + else: + print(f"WARNING: Frame footer {debug_hex(FRAME_FOOTER)} not found in binary data") + + # Process the binary data + return process_binary_data(binary_data) + line = "" + elif c == b'\r': + pass # Ignore CR characters + else: + # Normal text processing + if c == b'\n': + # Check if this line is the start marker + if BINARY_START_MARKER in line: + print("Binary start marker detected") + in_binary_section = True + binary_data = bytearray() + line = "" + else: + print(f"Log: {line}") + line = "" + else: + line += c.decode('ascii', errors='replace') + else: + # No data available, sleep briefly + time.sleep(0.01) + + except serial.SerialException as e: + print(f"Serial error: {e}") + return None + except Exception as e: + print(f"Unexpected error: {e}") + import traceback + traceback.print_exc() + return None + +def process_binary_data(data): + """Process the binary data to extract the frame.""" + print(f"Processing {len(data)} bytes of binary data") + + # Search for the frame header + header_pos = -1 + for i in range(len(data) - len(FRAME_HEADER)): + if data[i:i+len(FRAME_HEADER)] == FRAME_HEADER: + header_pos = i + break + + if header_pos == -1: + print("Error: Frame header not found") + return None + + print(f"Frame header found at position {header_pos}") + + # Extract the frame size + size_start = header_pos + len(FRAME_HEADER) + size_bytes = data[size_start:size_start+4] + if len(size_bytes) < 4: + print("Error: Incomplete size bytes") + return None + + frame_size = struct.unpack(' -#include +#include #include "cstring" // Frame header and footer markers for synchronization - using distinctive values const uint8_t FRAME_HEADER[] = {0xDE, 0xAD, 0xBE, 0xEF}; // Distinctive header const uint8_t FRAME_FOOTER[] = {0xCA, 0xFE, 0xBA, 0xBE}; // Distinctive footer const int FRAME_MARKER_SIZE = 4; +uint8_t frame_buffer[160 * 120 * 2]; // Buffer for the image data // PIO2 is reserved for the cam data retreive functions -camera_config_t left_eye_config = { - .pin_pwdn = -1, /*!< GPIO pin for camera power down line */ //? Also called PWDN, or set to -1 and tie to GND - .pin_reset = -1, /*!< GPIO pin for camera reset line */ //? Cam reset, or set to -1 and tie to 3.3V - .pin_xclk = 25, /*!< GPIO pin for camera XCLK line */ //? in theory could be shared or perhaps ommited? - .pin_sccb_sda = 26, /*!< GPIO pin for camera SDA line */ - .pin_sccb_scl = 27, /*!< GPIO pin for camera SCL line */ - .pin_data_base = 28, /*!< this pin + 7 consecutive will be used D0-D7 PCLK HREF */ - .pin_vsync = 39, /*!< GPIO pin for camera VSYNC line */ - .sccb_ctrl = 1, /* Select i2c controller ctrl: 0 - i2c0, 1 - i2c1, 2 - pio0, 3 - pio1, 4 - pio2 */ -}; - +// camera_config_t left_eye_config = { +// .pin_pwdn = -1, /*!< GPIO pin for camera power down line */ //? Also called PWDN, or set to -1 and tie to GND +// .pin_reset = -1, /*!< GPIO pin for camera reset line */ //? Cam reset, or set to -1 and tie to 3.3V +// .pin_xclk = 3, /*!< GPIO pin for camera XCLK line */ //? in theory could be shared or perhaps ommited? +// .pin_sccb_sda = 4, /*!< GPIO pin for camera SDA line */ +// .pin_sccb_scl = 5, /*!< GPIO pin for camera SCL line */ +// .pin_data_base = 6, /*!< this pin + 7 consecutive will be used D0-D7 PCLK HREF */ +// .pin_vsync = 16, /*!< GPIO pin for camera VSYNC line */ +// .xclk_div = 4, /*!< Frequency of XCLK signal, in Hz. */ //! Figure out the highest it can go to +// .sccb_ctrl = 0, /* Select i2c controller ctrl: 0 - i2c0, 1 - i2c1, 2 - pio0, 3 - pio1, 4 - pio2 */ +// }; +ov2640_config left_eye_config = { + .sccb = i2c0, /*!< I2C controller for camera SCCB */ + .pin_sioc = 32, /*!< GPIO pin for camera SCCB SIOC line */ + .pin_siod = 33, /*!< GPIO pin for camera SCCB SIOD line */ + .pin_resetb = 0, /*!< GPIO pin for camera reset line */ //? Cam reset, or set to -1 and tie to 3.3V + .pin_xclk = 31, /*!< GPIO pin for camera XCLK line */ //? in theory could be shared or perhaps ommited? + .pin_vsync = 44, /*!< GPIO pin for camera VSYNC line */ + .pin_y2_pio_base = 34, /*!< this pin + 7 consecutive will be used D0-D7 PCLK HREF */ + .pio = pio2, /*!< PIO instance for camera data reception */ + .pio_sm = 0, /*!< PIO state machine number for camera data reception */ + .dma_channel = 0, /*!< DMA channel number for camera data reception */ + .image_buf = frame_buffer, /*!< Pointer to the image buffer (to be allocated later) */ + .image_buf_size = sizeof(frame_buffer) // Size of the image buffer (160x120 RGB565) +}; // Send a properly framed image using printf for binary data void send_frame(const void* buffer, size_t size) { // Ensure UART output buffer is flushed before sending binary data @@ -42,7 +57,6 @@ void send_frame(const void* buffer, size_t size) { // Send frame header fwrite(FRAME_HEADER, 1, FRAME_MARKER_SIZE, stdout); sleep_ms(100); // Small delay to ensure the text is transmitted separately - printf("test...."); // Send frame size (4 bytes, little-endian) uint8_t size_bytes[4]; @@ -51,7 +65,6 @@ void send_frame(const void* buffer, size_t size) { size_bytes[2] = (size >> 16) & 0xFF; size_bytes[3] = (size >> 24) & 0xFF; fwrite(size_bytes, 1, 4, stdout); - printf("test2...."); // Calculate checksum uint32_t checksum = 0; @@ -113,8 +126,13 @@ int main() printf("Configuring Camera...\n"); - OV2640 left_cam = OV2640(left_eye_config); - left_cam.begin(DMA_IRQ_0, 2); // 0 for RGB565 mode + //OV2640 left_cam = OV2640(left_eye_config); + ov2640_init(&left_eye_config); + ov2640_reg_write(&left_eye_config, 0xff, 0x01); + uint8_t midh = ov2640_reg_read(&left_eye_config, 0x1C); + uint8_t midl = ov2640_reg_read(&left_eye_config, 0x1D); + printf("MIDH = 0x%02x, MIDL = 0x%02x\n", midh, midl); + // left_cam.begin(DMA_IRQ_0,1); // 0 for RGB565 mode printf("Camera Configured!...\n"); // Image size (160 x 120 x 2 bytes per pixel for RGB565) @@ -123,13 +141,14 @@ int main() while (true) { // Capture a frame printf("Attempting to capture frame...\n"); - left_cam.capture_frame(); - + //left_cam.capture_frame(); + ov2640_capture_frame(&left_eye_config); // Once the frame is ready, send it over UART printf("Checking if frame is ready...\n"); printf("Frame ready, sending...\n"); - send_frame(left_cam.fb, frame_size); - left_cam.resetFrameReady(); + //send_frame(left_cam.fb, frame_size); + //left_cam.resetFrameReady(); + send_frame(left_eye_config.image_buf, frame_size); printf("Frame sent...\n"); diff --git a/src/ov2640/SCCB.cpp b/src/ov2640/SCCB.cpp index b3f3a75..a927950 100644 --- a/src/ov2640/SCCB.cpp +++ b/src/ov2640/SCCB.cpp @@ -12,7 +12,7 @@ SCCB::SCCB(uint8_t sda_pin, uint8_t scl_pin) { SCCB::~SCCB() {} -// ctrl: 0 - i2c0, 1 - i2c1, 2 - pio0, 3 - pio1, 4 - pio2 +// ctrl: 0 - i2c0, 1 - i2c1, 2 - pio0, 3 - pio1, 4 - pio1 // TODO: add proper return values when failure // TODO: panic if scl != sda + 1 int SCCB::begin(uint8_t ctrl) @@ -38,7 +38,7 @@ int SCCB::begin(uint8_t ctrl) this->pio = pio1; break; case 4: - this->pio = pio2; + this->pio = pio1; break; default: this->pio = pio0; diff --git a/src/ov2640/camera.cpp b/src/ov2640/camera.cpp index d4bea2d..d68dccd 100644 --- a/src/ov2640/camera.cpp +++ b/src/ov2640/camera.cpp @@ -14,44 +14,56 @@ #include "src/pio/image/image.pio.h" -static volatile bool frameReady = false; // true at end-of-frame -static volatile bool suspended = true; -static volatile bool dma_busy = false; // true when DMA transfer is done -static void* pointer; +static volatile bool frameReady = false; +static volatile bool suspended = true; +static volatile bool dma_busy = false; +void* pointer; -static void iCap_vsync_irq(uint gpio, uint32_t events) { - if (!suspended) { - // Clear PIO FIFOs and start DMA transfer - pio_sm_clear_fifos(pio2, 0); - dma_channel_start(0); +void iCap_vsync_irq(uint gpio, uint32_t events) { + if (events & GPIO_IRQ_EDGE_RISE) { + //printf("VSYNC RISE (suspended=%d, dma_busy=%d)\n", suspended, dma_busy); + + // Only start capture on rising edge of VSYNC if we're not suspended and DMA isn't busy + if (!suspended && !dma_busy) { + // Fill test pattern to verify DMA is running + uint16_t* fb_ptr = (uint16_t*)pointer; + for (int i = 0; i < 10; i++) { + fb_ptr[i] = 0xAA55; // Test pattern + } + + pio_sm_clear_fifos(pio1, 0); // Clear PIO FIFOs + dma_busy = true; // Mark DMA as busy + printf("Starting DMA transfer\n"); + dma_channel_start(0); // Start DMA transfer + } } - } +} -static void iCap_dma_finish_irq() { - frameReady = true; - suspended = true; - dma_channel_set_write_addr(0, (uint8_t *)(pointer), false); - dma_hw->ints0 = 1u << 0; +// DMA completion interrupt handler +void iCap_dma_finish_irq() { + frameReady = true; // Signal frame is ready + suspended = true; // Suspend further captures + dma_busy = false; // DMA is no longer busy + + // Check if data was received + uint16_t* fb_ptr = (uint16_t*)pointer; + uint32_t non_zero_count = 0; + for (int i = 0; i < 100; i++) { // Just check first 100 values + if (fb_ptr[i] != 0) { + non_zero_count++; + } + } + printf("DMA complete: %d/100 non-zero values found\n", non_zero_count); + + dma_channel_set_write_addr(0, pointer, false); // Reset write address + dma_hw->ints0 = 1u << 0; // Clear DMA interrupt flag } -// TODO: Stolen from Adafruit repo (Check if correct) - -// PIO code in this table is modified at runtime so that PCLK is -// configurable (rather than fixed GP## or PIN offset). Data pins -// must be contiguous but are otherwise configurable. -static uint16_t capture_pio_opcodes[] = { - // Only monitor PCLK when HSYNC is high. This is more noise-immune - // than letting it fly. - 0b0010000010000000, // WAIT 1 GPIO 0 (mask in HSYNC pin before use) - 0b0010000010000000, // WAIT 1 GPIO 0 (mask in PCLK pin before use) - 0b0100000000001000, // IN PINS 8 -- 8 bits into RX FIFO - 0b0010000000000000, // WAIT 0 GPIO 0 (mask in PCLK pin before use) -}; static struct pio_program cap_pio_program = { - .instructions = capture_pio_opcodes, - .length = sizeof capture_pio_opcodes / sizeof capture_pio_opcodes[0], + .instructions = image_program_instructions, + .length = sizeof image_program_instructions / sizeof image_program_instructions[0], .origin = -1, }; @@ -624,8 +636,8 @@ int OV2640::begin(int dma_irq, int mode) // mode is just here to make debbuging gpio_set_function(this->config.pin_xclk, GPIO_FUNC_PWM); uint slice_num = pwm_gpio_to_slice_num(this->config.pin_xclk); - pwm_set_wrap(slice_num, this->config.xclk_div - 1); - pwm_set_gpio_level(this->config.xclk_div / 2, 4); + pwm_set_wrap(slice_num, this->config.xclk_div); + pwm_set_gpio_level(this->config.pin_xclk, 4); pwm_set_enabled(slice_num, true); // Init SCCB @@ -641,7 +653,7 @@ int OV2640::begin(int dma_irq, int mode) // mode is just here to make debbuging printf("Sending camera reset command...\n"); this->sccb.writeRegister(OV2640_REG_RA_DLMT, OV2640_RA_DLMT_SENSOR); // Bank select 1 this->sccb.writeRegister(OV2640_REG1_COM7, OV2640_COM7_SRST); // System reset< - printf("Camera reset complete\n"); + sleep_ms(300); switch(mode) { case 0: @@ -672,93 +684,27 @@ int OV2640::begin(int dma_irq, int mode) // mode is just here to make debbuging } //prtintf("Gpio init done\n"); - // PIO periph to use is currently specified by the user in the arch struct, - // but I suppose this could be written to use whatever PIO has resources. - // Mask the GPIO pin used PCLK into the PIO opcodes -- see notes at top - // TODO: check if this is correct (code made for rp2040 not rp2350 so it might differ) - //prtintf("PIO init\n"); - //! Temporary replace with the image.pio from known working library rp2040_ov2640 - /*capture_pio_opcodes[0] |= (this->config.pin_href & 31); - capture_pio_opcodes[1] |= (this->config.pin_pclk & 31); - capture_pio_opcodes[3] |= (this->config.pin_pclk & 31); + printf("Setting up PIO for image capture...\n"); + uint offset = pio_add_program(pio1, &cap_pio_program); + image_program_init(pio1, 0, offset, this->config.pin_data_base); + printf("PIO setup complete\n"); - uint offset = pio_add_program(pio2, &cap_pio_program); - this->sm = pio_claim_unused_sm(pio2, true); // 0-3 - sm = this->sm; - pio_sm_set_consecutive_pindirs(pio2, this->sm, this->config.pin_data_base, 8, false); - - pio_sm_config c = pio_get_default_sm_config(); - c.pinctrl = 0; // SDK fails to set this - sm_config_set_wrap(&c, offset, offset + cap_pio_program.length - 1); - - sm_config_set_in_pins(&c, this->config.pin_data_base); - sm_config_set_in_shift(&c, false, true, 16); // 1 pixel (16b) ISR to FIFO - sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_RX); - - pio_sm_init(pio2, this->sm, offset, &c); - pio_sm_set_enabled(pio2, this->sm, true); - //prtintf("PIO init done\n"); - - // SET UP DMA ------------------------------------------------------------ - //prtintf("DMA init\n"); - this->dma_channel = dma_claim_unused_channel(false); // don't panic - dma_channel = this->dma_channel; - this->dma_config = dma_channel_get_default_config(this->dma_channel); - channel_config_set_transfer_data_size(&this->dma_config, DMA_SIZE_16); - channel_config_set_read_increment(&this->dma_config, false); - channel_config_set_write_increment(&this->dma_config, true); - channel_config_set_bswap(&this->dma_config, true); - - // Set PIO RX as DMA trigger. Input shift register saturates at 16 bits - // (1 pixel), configured in data size above and in PIO setup elsewhere. - channel_config_set_dreq(&this->dma_config, - pio_get_dreq(pio2, this->sm, false)); - // Set up baseline DMA configuration...it's initially lacking destination - // and count, set later (dma_change()) after resolution is known. DMA - // isn't started until later, and is triggered in the vsync interrupt. - dma_channel_configure(this->dma_channel, &this->dma_config, NULL, - &pio2->rxf[this->sm], 0, false); - - // Set up end-of-DMA interrupt - dma_channel_set_irq0_enabled(this->dma_channel, true); - //prtintf("DMA init done\n"); - //? setup diffrent handlers for each cam??? - //? check with a button or smth if this fires all events or only one - //? cuz then I would be able to do dma_finish_irq_cam1, dma_finish_irq_cam2, dma_finish_irq_cam3 - //? That would have hardcoded values for the buffers - irq_set_exclusive_handler(dma_irq, dma_finish_irq); - irq_set_enabled(dma_irq, true); - - // SET UP VSYNC INTERRUPT ------------------------------------------------ - //? This also could be redone with hardcoded values - gpio_set_irq_enabled_with_callback(this->config.pin_vsync, GPIO_IRQ_EDGE_RISE, true, - &vsync_irq);*/ - - uint offset = pio_add_program(pio2, &image_program); - image_program_init(pio2, 0, offset, this->config.pin_data_base); - - //printf("IRQ init done\n"); - - //printf("config done"); + // DMA setup + printf("Configuring DMA for image capture...\n"); dma_channel_config c = dma_channel_get_default_config(0); channel_config_set_transfer_data_size(&c, DMA_SIZE_16); channel_config_set_read_increment(&c, false); channel_config_set_write_increment(&c, true); channel_config_set_bswap(&c, true); - // Set PIO RX as DMA trigger. Input shift register saturates at 16 bits - // (1 pixel), configured in data size above and in PIO setup elsewhere. - channel_config_set_dreq(&c, - pio_get_dreq(pio2, 0, false)); - // Set up baseline DMA configuration...it's initially lacking destination - // and count, set later (dma_change()) after resolution is known. DMA - // isn't started until later, and is triggered in the vsync interrupt. - dma_channel_configure(0, &c, &this->fb, - &pio2->rxf[0], sizeof(this->fb), false); - - // Set up end-of-DMA interrupt + channel_config_set_dreq(&c, pio_get_dreq(pio1, 0, false)); + dma_channel_configure(0, &c, this->fb, &pio1->rxf[0], 160 * 120*2, false); + printf("DMA configuration complete\n"); + + // Set up DMA interrupt + printf("Setting up DMA interrupt...\n"); dma_channel_set_irq0_enabled(0, true); - irq_set_exclusive_handler(DMA_IRQ_0, iCap_dma_finish_irq); + irq_set_exclusive_handler(DMA_IRQ_0, iCap_dma_finish_irq); // Register DMA handler irq_set_enabled(DMA_IRQ_0, true); printf("DMA interrupt setup complete\n"); @@ -768,7 +714,9 @@ int OV2640::begin(int dma_irq, int mode) // mode is just here to make debbuging &iCap_vsync_irq); // Register VSYNC handler printf("VSYNC interrupt setup complete\n"); + // ============= TESTING ========================================================= // Test if VSYNC is toggling + // ================================================================================ printf("Checking if VSYNC is toggling...\n"); bool initial_vsync = gpio_get(this->config.pin_vsync); uint32_t start_time = time_us_32(); @@ -782,13 +730,41 @@ int OV2640::begin(int dma_irq, int mode) // mode is just here to make debbuging } sleep_ms(1); } - + if (!vsync_changed) { printf("WARNING: VSYNC signal not detected during initialization\n"); } else { printf("VSYNC signal detected successfully\n"); } + // Add after VSYNC check + printf("Testing data pins for signal...\n"); + uint32_t last_values[10] = {0}; + bool data_changing = false; + + for (int i = 0; i < 1000; i++) { + bool changed = false; + for (int pin = 0; pin < 10; pin++) { + uint32_t val = gpio_get(this->config.pin_data_base + pin); + if (val != last_values[pin]) { + changed = true; + last_values[pin] = val; + } + } + if (changed) { + data_changing = true; + printf("Data pins showing activity\n"); + break; + } + sleep_ms(1); + } + + if (!data_changing) { + printf("ERROR: No activity detected on data pins!\n"); + } + // ================================================================================ + // ================================================================================ + printf("Camera initialization complete\n"); return 0; } @@ -868,44 +844,55 @@ void OV2640::resetFrameReady() { } void OV2640::capture_frame() { + // Reset frame buffer with a known pattern + uint16_t* fb_ptr = (uint16_t*)this->fb; + for (int i = 0; i < 160 * 120; i++) { + fb_ptr[i] = 0; // Clear to zero + } + + // Add test pattern to verify data is changed + for (int i = 0; i < 10; i++) { + fb_ptr[i] = 0x1234 + i; // Test pattern + } + + printf("Starting frame capture (suspended=%d, frameReady=%d)\n", suspended, frameReady); + frameReady = false; + + // Important: Enable capture by setting suspended to false suspended = false; - // Wait for frame with timeout to prevent infinite loops + // Reset DMA in case it was left in a bad state + dma_channel_abort(0); + dma_busy = false; + dma_channel_set_write_addr(0, this->fb, false); + + // Wait for frame with timeout uint32_t start_time = time_us_32(); uint32_t timeout_us = 2000000; // 2 second timeout + // Monitor pin states during capture + int report_interval = 0; while(!frameReady) { + // Report activity periodically + if (report_interval++ % 1000 == 0) { + printf("Waiting for frame: VSYNC=%d HREF=%d PCLK=%d\n", + gpio_get(this->config.pin_vsync), + gpio_get(this->config.pin_vsync-1), + gpio_get(this->config.pin_vsync-2)); + } + // Check for timeout if ((time_us_32() - start_time) > timeout_us) { - printf("Frame capture timeout! Sending incomplete frame...\n"); - // Reset DMA in case it's stuck + printf("Frame capture timeout!\n"); dma_channel_abort(0); - dma_channel_set_write_addr(0, pointer, false); dma_busy = false; suspended = true; - return; // Exit without waiting for frameReady + return; } + // Small yield to avoid tight loop sleep_us(100); } - // Frame is ready, no need to do anything else - // The DMA handler has already set frameReady = true printf("Frame captured successfully\n"); -} - - -//! https://forums.raspberrypi.com/viewtopic.php?t=339299 -// TODO: change to switches and experiment with state machines, check if I can kinda reserve dma's so 0-3 would indicate state machines 0-3 -/* Read the flags -pio0_hw->irq; -uint32_t flags = read_register(PIO0_BASE, PIO_IRQ_OFFSET) -// Check the flags to determine which state machine made the request -if (flags & 0b0001) { handle_sm_0(); } -if (flags & 0b0010) { handle_sm_1(); } -if (flags & 0b0100) { handle_sm_2(); } -if (flags & 0b1000) { handle_sm_3(); } -*/ - -// TODO: add all of the specific controls like brightness and all of that scheiße -// THERE ARE MORE COMMENTS THEN ACTUAL CODE AT THIS POINT??? \ No newline at end of file +} \ No newline at end of file diff --git a/src/pio/image/image.pio.h b/src/pio/image/image.pio.h deleted file mode 100644 index 7e7a3fd..0000000 --- a/src/pio/image/image.pio.h +++ /dev/null @@ -1,64 +0,0 @@ -// -------------------------------------------------- // -// This file is autogenerated by pioasm; do not edit! // -// -------------------------------------------------- // - -#pragma once - -#if !PICO_NO_HARDWARE -#include "hardware/pio.h" -#endif - -// ----- // -// image // -// ----- // - -#define image_wrap_target 0 -#define image_wrap 3 -#define image_pio_version 1 - -// static const uint16_t image_program_instructions[] = { -// // .wrap_target -// 0x20a9, // 0: wait 1 pin, 9 -// 0x20a8, // 1: wait 1 pin, 8 -// 0x4008, // 2: in pins, 8 -// 0x2028, // 3: wait 0 pin, 8 -// // .wrap -// }; -static const uint16_t image_program_instructions[] = { - // .wrap_target - 0x20a9, // 0: wait 1 pin, 9 - 0x20a8, // 1: wait 1 pin, 8 - 0x4008, // 2: in pins, 8 - 0x2028, // 3: wait 0 pin, 8 - // .wrap -}; - -#if !PICO_NO_HARDWARE -static const struct pio_program image_program = { - .instructions = image_program_instructions, - .length = 4, - .origin = -1, - .pio_version = image_pio_version, -#if PICO_PIO_VERSION > 0 - .used_gpio_ranges = 0x0 -#endif -}; - -static inline pio_sm_config image_program_get_default_config(uint offset) { - pio_sm_config c = pio_get_default_sm_config(); - sm_config_set_wrap(&c, offset + image_wrap_target, offset + image_wrap); - return c; -} - -void image_program_init(PIO pio, uint sm, uint offset, uint pin_base) { - pio_sm_set_consecutive_pindirs(pio, sm, pin_base, 10, false); - pio_sm_config c = image_program_get_default_config(offset); - sm_config_set_in_pins(&c, pin_base); - sm_config_set_in_shift(&c, false, true, 16); // TODO: if something is not working check this i.e revert back to 8 together with dma transfer - sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_RX); - pio_sm_init(pio, sm, offset, &c); - pio_sm_set_enabled(pio, sm, true); -} - -#endif - diff --git a/src/rp2040/SCCB.cpp b/src/rp2040/SCCB.cpp new file mode 100644 index 0000000..a927950 --- /dev/null +++ b/src/rp2040/SCCB.cpp @@ -0,0 +1,105 @@ +#include +#include +#include "hardware/i2c.h" +#include "pico/stdlib.h" +#include "stdio.h" +#include "src/pio/i2c/pio_i2c.h" + +SCCB::SCCB(uint8_t sda_pin, uint8_t scl_pin) { + this->sda = sda_pin; + this->scl = scl_pin; +} + +SCCB::~SCCB() {} + +// ctrl: 0 - i2c0, 1 - i2c1, 2 - pio0, 3 - pio1, 4 - pio1 +// TODO: add proper return values when failure +// TODO: panic if scl != sda + 1 +int SCCB::begin(uint8_t ctrl) +{ + // Set up XCLK out unless it's a self-clocking camera. This must be done + // BEFORE any I2C commands, as cam may require clock for I2C timing. + this->ctrl = ctrl; + if (ctrl < 2) { + this->i2cc = ctrl == 0 ? i2c0 : i2c1; + i2c_init(this->i2cc, 100 * 1000); + gpio_set_function(this->sda, GPIO_FUNC_I2C); + gpio_set_function(this->scl, GPIO_FUNC_I2C); + gpio_pull_up(this->sda); + gpio_pull_up(this->scl); + } + else { + PIO pio; + switch (ctrl) { + case 2: + this->pio = pio0; + break; + case 3: + this->pio = pio1; + break; + case 4: + this->pio = pio1; + break; + default: + this->pio = pio0; + break; + }; + + uint sm = pio_claim_unused_sm(this->pio, true); + uint offset = pio_add_program(this->pio, &i2c_program); + i2c_program_init(this->pio, this->sm, offset, this->sda, this->scl); + } + + return 0; +} + +int SCCB::readRegister(uint8_t reg) +{ + uint8_t buf[1]; + if (this->ctrl < 2) { + i2c_write_blocking(this->i2cc, OV2640_ADDR, ®, 1, true); // TODO: check if true or false is correct here + i2c_read_blocking(this->i2cc, OV2640_ADDR, buf, 1, false); // false - finished with bus + }else { + //pio_i2c_write_blocking(this->pio, this->sm, OV2640_ADDR, ®, 1); + //pio_i2c_read_blocking(this->pio, this->sm, OV2640_ADDR, buf, 1); + } + return buf[0]; +} + +void SCCB::writeRegister(uint8_t reg, uint8_t value) +{ + uint8_t buf[2]; + buf[0] = reg; + buf[1] = value; + + if (this->ctrl < 2) { + int ret = i2c_write_blocking(this->i2cc, OV2640_ADDR, buf, 2, false); + if(ret == PICO_ERROR_GENERIC) { + printf("Problem i2c write failed!"); + sleep_ms(1000); + } + }else { + //pio_i2c_write_blocking(this->pio, this->sm, OV2640_ADDR, buf, 2); + } +} + +void SCCB::writeMaskRegister(uint8_t reg, uint8_t offset, uint8_t mask, uint8_t value) +{ + uint8_t buf[2]; + buf[0] = reg; + buf[1] = value; + + uint8_t old_val = this->readRegister(reg); + uint8_t new_value = (old_val & ~(mask << offset)) | ((value & mask) << offset); + this->writeRegister(reg, new_value); +} + +void SCCB::writeList(const register_val_t *cfg, + uint16_t len) +{ + for (int i = 0; i < len; i++) + { + writeRegister(cfg[i].reg, cfg[i].value); + sleep_ms(2); // Some cams require, else lockup on init + } +} \ No newline at end of file diff --git a/src/rp2040/SCCB.hpp b/src/rp2040/SCCB.hpp new file mode 100644 index 0000000..9b6ec09 --- /dev/null +++ b/src/rp2040/SCCB.hpp @@ -0,0 +1,30 @@ +#include +#include "pico/stdlib.h" +#include "hardware/i2c.h" +#include "hardware/pio.h" + +typedef struct { + uint8_t reg; ///< Register address + uint8_t value; ///< Value to store +} register_val_t; + +class SCCB { +public: + SCCB(uint8_t sda_pin = 0, uint8_t scl_pin = 0); + ~SCCB(); // Destructor + + int begin(uint8_t ctrl); + + int readRegister(uint8_t reg); + void writeRegister(uint8_t reg, uint8_t value); + void writeMaskRegister(uint8_t reg, uint8_t offset, uint8_t mask, uint8_t value); + void writeList(const register_val_t *cfg, uint16_t len); + +private: + uint8_t sda; + uint8_t scl; + int ctrl; + i2c_inst_t* i2cc; + pio_hw_t* pio; + int sm; +}; \ No newline at end of file diff --git a/src/rp2040/ov2640.cpp b/src/rp2040/ov2640.cpp new file mode 100644 index 0000000..5145157 --- /dev/null +++ b/src/rp2040/ov2640.cpp @@ -0,0 +1,140 @@ +#define OV2640_REG_RA_DLMT 0xFF //< Register bank select +#define OV2640_RA_DLMT_SENSOR 0x01 //< Bank 1 - Sensor address +#define OV2640_REG1_COM7 0x12 //< Common control 7: +#define OV2640_COM7_SRST 0x80 //< System reset +#define OV2640_COM7_COLORBAR 0x02 //< Color bar test pattern enable + +#include + +#include "ov2640.hpp" +#include +#include "ov2640_init.h" +#include "hardware/dma.h" +#include "hardware/i2c.h" +#include "hardware/pwm.h" +#include "image.pio.h" + + +static const uint8_t OV2640_ADDR = 0x60 >> 1; + +void ov2640_init(struct ov2640_config *config) { + // XCLK generation (~20.83 MHz) + gpio_set_function(config->pin_xclk, GPIO_FUNC_PWM); + uint slice_num = pwm_gpio_to_slice_num(config->pin_xclk); + // 6 cycles (0 to 5), 125 MHz / 6 = ~20.83 MHz wrap rate + pwm_set_wrap(slice_num, 5); + pwm_set_gpio_level(config->pin_xclk, 4); + pwm_set_enabled(slice_num, true); +gpio_pull_down(config->pin_vsync); + // // printf("Setting up GPIO pins for camera data...\n"); + // gpio_init(config->pin_vsync); + // gpio_set_dir(config->pin_vsync, GPIO_IN); + // //gpio_pull_up(config->pin_vsync); + // for (uint8_t i = 0; i < 10; i++) + // { + // gpio_init(config->pin_y2_pio_base + i); + // gpio_set_dir(config->pin_y2_pio_base + i, GPIO_IN); + // //gpio_pull_down(this->config.pin_data_base + i); + // } + + + + + // SCCB I2C @ 100 kHz + // gpio_set_function(config->pin_sioc, GPIO_FUNC_I2C); + // gpio_set_function(config->pin_siod, GPIO_FUNC_I2C); + // i2c_init(config->sccb, 100 * 1000); + + // Initialise reset pin + gpio_init(config->pin_resetb); + gpio_set_dir(config->pin_resetb, GPIO_OUT); + + // Reset camera, and give it some time to wake back up + // gpio_put(config->pin_resetb, 0); + // sleep_ms(100); + // gpio_put(config->pin_resetb, 1); + // sleep_ms(100); + // Init SCCB + SCCB sccb = SCCB(config->pin_siod, config->pin_sioc); + sccb.begin(0); + printf("Sending camera reset command...\n"); + const uint8_t bank_select[] = {OV2640_REG_RA_DLMT, OV2640_RA_DLMT_SENSOR}; + const uint8_t system_reset[] = {OV2640_REG1_COM7, OV2640_COM7_SRST}; + ov2640_regs_write(config, &bank_select); // Bank select 1 + ov2640_regs_write(config, &system_reset); // System reset + sleep_ms(300); + printf("OV2640 camera reset\n"); + // Initialise the camera itself over SCCB + ov2640_regs_write(config, ov2640_vga); + printf("OV2640 Set VGA\n"); + ov2640_regs_write(config, ov2640_uxga_cif); + printf("OV2640 Set UXAG\n"); + + // // Set RGB565 output mode + ov2640_reg_write(config, 0xff, 0x00); + // printf("OV2640 Set RGB\n"); + + ov2640_reg_write(config, 0xDA, (ov2640_reg_read(config, 0xDA) & 0xC) | 0x8); + + // Enable image RX PIO + uint offset = pio_add_program(config->pio, &image_program); + printf("PIO offset: %d\n", offset); + + offset = 28; + image_program_init(config->pio, config->pio_sm, offset, config->pin_y2_pio_base); +} + +void ov2640_capture_frame(struct ov2640_config *config) { + dma_channel_config c = dma_channel_get_default_config(config->dma_channel); + channel_config_set_read_increment(&c, false); + channel_config_set_write_increment(&c, true); + channel_config_set_dreq(&c, pio_get_dreq(config->pio, config->pio_sm, false)); + channel_config_set_transfer_data_size(&c, DMA_SIZE_8); + + dma_channel_configure( + config->dma_channel, &c, + config->image_buf, + &config->pio->rxf[config->pio_sm], + config->image_buf_size, + false + ); + + // Wait for vsync rising edge to start frame + printf("Waiting for vsync...\n"); + while (gpio_get(config->pin_vsync) == true); + printf("Vsync detected, starting DMA...\n"); + while (gpio_get(config->pin_vsync) == false); + printf("Vsync Finished, starting DMA...\n"); + + dma_channel_start(config->dma_channel); + dma_channel_wait_for_finish_blocking(config->dma_channel); +} + +void ov2640_reg_write(struct ov2640_config *config, uint8_t reg, uint8_t value) { + uint8_t data[] = {reg, value}; + i2c_write_blocking(config->sccb, OV2640_ADDR, data, sizeof(data), false); +} + +uint8_t ov2640_reg_read(struct ov2640_config *config, uint8_t reg) { + i2c_write_blocking(config->sccb, OV2640_ADDR, ®, 1, false); + + uint8_t value; + i2c_read_blocking(config->sccb, OV2640_ADDR, &value, 1, false); + + return value; +} + +void ov2640_regs_write(struct ov2640_config *config, const uint8_t (*regs_list)[2]) { + while (1) { + uint8_t reg = (*regs_list)[0]; + uint8_t value = (*regs_list)[1]; + + if (reg == 0x00 && value == 0x00) { + break; + } + + ov2640_reg_write(config, reg, value); + + regs_list++; + } +} \ No newline at end of file diff --git a/src/rp2040/ov2640.hpp b/src/rp2040/ov2640.hpp new file mode 100644 index 0000000..267aee0 --- /dev/null +++ b/src/rp2040/ov2640.hpp @@ -0,0 +1,36 @@ +#ifndef OV2640_H +#define OV2640_H +#include +#include "pico/stdlib.h" +#include "hardware/i2c.h" +#include "hardware/pio.h" + + +struct ov2640_config { + i2c_inst_t *sccb; + uint pin_sioc; + uint pin_siod; + + uint pin_resetb; + uint pin_xclk; + uint pin_vsync; + // Y2, Y3, Y4, Y5, Y6, Y7, Y8, PCLK, HREF + uint pin_y2_pio_base; + + PIO pio; + uint pio_sm; + + uint dma_channel; + uint8_t *image_buf; + size_t image_buf_size; +}; + +void ov2640_init(struct ov2640_config *config); + +void ov2640_capture_frame(struct ov2640_config *config); + +void ov2640_reg_write(struct ov2640_config *config, uint8_t reg, uint8_t value); +uint8_t ov2640_reg_read(struct ov2640_config *config, uint8_t reg); +void ov2640_regs_write(struct ov2640_config *config, const uint8_t (*regs_list)[2]); + +#endif \ No newline at end of file diff --git a/src/rp2040/ov2640_init.h b/src/rp2040/ov2640_init.h new file mode 100644 index 0000000..5e010d7 --- /dev/null +++ b/src/rp2040/ov2640_init.h @@ -0,0 +1,265 @@ +#ifndef OV2640_INIT_H +#define OV2640_INIT_H +#include + +static const uint8_t ov2640_vga[][2] = { + {0xff, 0x00}, /* Device control register list Table 12 */ + {0x2c, 0xff}, /* Reserved */ + {0x2e, 0xdf}, /* Reserved */ + {0xff, 0x01}, /* Device control register list Table 13 */ + {0x3c, 0x32}, /* Reserved */ + {0x11, 0x00}, /* Clock Rate Control */ + {0x09, 0x02}, /* Common control 2 */ + {0x04, 0xA8}, /* Mirror */ + {0x13, 0xe5}, /* Common control 8 */ + {0x14, 0x48}, /* Common control 9 */ + {0x2c, 0x0c}, /* Reserved */ + {0x33, 0x78}, /* Reserved */ + {0x3a, 0x33}, /* Reserved */ + {0x3b, 0xfB}, /* Reserved */ + {0x3e, 0x00}, /* Reserved */ + {0x43, 0x11}, /* Reserved */ + {0x16, 0x10}, /* Reserved */ + {0x4a, 0x81}, /* Reserved */ + {0x21, 0x99}, /* Reserved */ + {0x24, 0x40}, /* Luminance signal High range */ + {0x25, 0x38}, /* Luminance signal low range */ + {0x26, 0x82}, /* */ + {0x5c, 0x00}, /* Reserved */ + {0x63, 0x00}, /* Reserved */ + {0x46, 0x3f}, /* Frame length adjustment */ + {0x0c, 0x3c}, /* Common control 3 */ + {0x61, 0x70}, /* Histogram algo low level */ + {0x62, 0x80}, /* Histogram algo high level */ + {0x7c, 0x05}, /* Reserved */ + {0x20, 0x80}, /* Reserved */ + {0x28, 0x30}, /* Reserved */ + {0x6c, 0x00}, /* Reserved */ + {0x6d, 0x80}, /* Reserved */ + {0x6e, 0x00}, /* Reserved */ + {0x70, 0x02}, /* Reserved */ + {0x71, 0x94}, /* Reserved */ + {0x73, 0xc1}, /* Reserved */ + {0x3d, 0x34}, /* Reserved */ + {0x5a, 0x57}, /* Reserved */ + {0x12, 0x00}, /* Common control 7 */ + {0x11, 0x00}, /* Clock Rate Control 2*/ + {0x17, 0x11}, /* Horiz window start MSB 8bits */ + {0x18, 0x75}, /* Horiz window end MSB 8bits */ + {0x19, 0x01}, /* Vert window line start MSB 8bits */ + {0x1a, 0x97}, /* Vert window line end MSB 8bits */ + {0x32, 0x36}, + {0x03, 0x0f}, + {0x37, 0x40}, + {0x4f, 0xbb}, + {0x50, 0x9c}, + {0x5a, 0x57}, + {0x6d, 0x80}, + {0x6d, 0x38}, + {0x39, 0x02}, + {0x35, 0x88}, + {0x22, 0x0a}, + {0x37, 0x40}, + {0x23, 0x00}, + {0x34, 0xa0}, + {0x36, 0x1a}, + {0x06, 0x02}, + {0x07, 0xc0}, + {0x0d, 0xb7}, + {0x0e, 0x01}, + {0x4c, 0x00}, + {0xff, 0x00}, + {0xe5, 0x7f}, + {0xf9, 0xc0}, + {0x41, 0x24}, + {0xe0, 0x14}, + {0x76, 0xff}, + {0x33, 0xa0}, + {0x42, 0x20}, + {0x43, 0x18}, + {0x4c, 0x00}, + {0x87, 0xd0}, + {0x88, 0x3f}, + {0xd7, 0x03}, + {0xd9, 0x10}, + {0xd3, 0x82}, + {0xc8, 0x08}, + {0xc9, 0x80}, + {0x7d, 0x00}, + {0x7c, 0x03}, + {0x7d, 0x48}, + {0x7c, 0x08}, + {0x7d, 0x20}, + {0x7d, 0x10}, + {0x7d, 0x0e}, + {0x90, 0x00}, + {0x91, 0x0e}, + {0x91, 0x1a}, + {0x91, 0x31}, + {0x91, 0x5a}, + {0x91, 0x69}, + {0x91, 0x75}, + {0x91, 0x7e}, + {0x91, 0x88}, + {0x91, 0x8f}, + {0x91, 0x96}, + {0x91, 0xa3}, + {0x91, 0xaf}, + {0x91, 0xc4}, + {0x91, 0xd7}, + {0x91, 0xe8}, + {0x91, 0x20}, + {0x92, 0x00}, + {0x93, 0x06}, + {0x93, 0xe3}, + {0x93, 0x02}, + {0x93, 0x02}, + {0x93, 0x00}, + {0x93, 0x04}, + {0x93, 0x00}, + {0x93, 0x03}, + {0x93, 0x00}, + {0x93, 0x00}, + {0x93, 0x00}, + {0x93, 0x00}, + {0x93, 0x00}, + {0x93, 0x00}, + {0x93, 0x00}, + {0x96, 0x00}, + {0x97, 0x08}, + {0x97, 0x19}, + {0x97, 0x02}, + {0x97, 0x0c}, + {0x97, 0x24}, + {0x97, 0x30}, + {0x97, 0x28}, + {0x97, 0x26}, + {0x97, 0x02}, + {0x97, 0x98}, + {0x97, 0x80}, + {0x97, 0x00}, + {0x97, 0x00}, + {0xc3, 0xef}, + {0xff, 0x00}, + {0xba, 0xdc}, + {0xbb, 0x08}, + {0xb6, 0x24}, + {0xb8, 0x33}, + {0xb7, 0x20}, + {0xb9, 0x30}, + {0xb3, 0xb4}, + {0xb4, 0xca}, + {0xb5, 0x43}, + {0xb0, 0x5c}, + {0xb1, 0x4f}, + {0xb2, 0x06}, + {0xc7, 0x00}, + {0xc6, 0x51}, + {0xc5, 0x11}, + {0xc4, 0x9c}, + {0xbf, 0x00}, + {0xbc, 0x64}, + {0xa6, 0x00}, + {0xa7, 0x1e}, + {0xa7, 0x6b}, + {0xa7, 0x47}, + {0xa7, 0x33}, + {0xa7, 0x00}, + {0xa7, 0x23}, + {0xa7, 0x2e}, + {0xa7, 0x85}, + {0xa7, 0x42}, + {0xa7, 0x33}, + {0xa7, 0x00}, + {0xa7, 0x23}, + {0xa7, 0x1b}, + {0xa7, 0x74}, + {0xa7, 0x42}, + {0xa7, 0x33}, + {0xa7, 0x00}, + {0xa7, 0x23}, + {0xc0, 0xc8}, + {0xc1, 0x96}, + {0x8c, 0x00}, + {0x86, 0x3d}, + {0x50, 0x92}, + {0x51, 0x90}, + {0x52, 0x2c}, + {0x53, 0x00}, + {0x54, 0x00}, + {0x55, 0x88}, + {0x5a, 0x50}, + {0x5b, 0x3c}, + {0x5c, 0x00}, + {0xd3, 0x04}, + {0x7f, 0x00}, + {0xda, 0x00}, + {0xe5, 0x1f}, + {0xe1, 0x67}, + {0xe0, 0x00}, + {0xdd, 0x7f}, + {0x05, 0x00}, + {0xff, 0x00}, + {0xe0, 0x04}, + {0xc0, 0xc8}, + {0xc1, 0x96}, + {0x86, 0x3d}, + {0x50, 0x92}, + {0x51, 0x90}, + {0x52, 0x2c}, + {0x53, 0x00}, + {0x54, 0x00}, + {0x55, 0x88}, + {0x57, 0x00}, + {0x5a, 0x50}, + {0x5b, 0x3c}, + {0x5c, 0x00}, + {0xd3, 0x04}, + {0xe0, 0x00}, + {0xFF, 0x00}, + {0x05, 0x00}, + {0xDA, 0x08}, + {0xda, 0x09}, + {0x98, 0x00}, + {0x99, 0x00}, + {0x00, 0x00}, + {0xff, 0x00}, + {0xe0, 0x04}, + {0xc0, 0xc8}, + {0xc1, 0x96}, + {0x86, 0x3d}, + {0x50, 0x89}, + {0x51, 0x90}, + {0x52, 0x2c}, + {0x53, 0x00}, + {0x54, 0x00}, + {0x55, 0x88}, + {0x57, 0x00}, + {0x5a, 0xA0}, + {0x5b, 0x78}, + {0x5c, 0x00}, + {0xd3, 0x02}, + {0xe0, 0x00} +}; + +static const uint8_t ov2640_uxga_cif[][2] = { + {0xff, 0x00}, + {0xe0, 0x04}, + {0xc0, 0xc8}, + {0xc1, 0x96}, + {0x86, 0x35}, + {0x50, 0x92}, + {0x51, 0x90}, + {0x52, 0x2c}, + {0x53, 0x00}, + {0x54, 0x00}, + {0x55, 0x88}, + {0x57, 0x00}, + {0x5a, 0x58}, + {0x5b, 0x48}, + {0x5c, 0x00}, + {0xd3, 0x08}, + {0xe0, 0x00} +}; + +#endif \ No newline at end of file