boards: Add OPENMV_AE3 board config files.

Signed-off-by: iabdalkader <i.abdalkader@gmail.com>
This commit is contained in:
iabdalkader 2024-02-06 21:48:16 +02:00
parent a90be859a5
commit 34a6027b10
9 changed files with 841 additions and 0 deletions

View File

@ -0,0 +1,188 @@
/*
* Copyright (C) 2023-2024 OpenMV, LLC.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Any redistribution, use, or modification in source or binary form
* is done solely for personal benefit and not for any commercial
* purpose or for monetary gain. For commercial licensing options,
* please contact openmv@openmv.io
*
* THIS SOFTWARE IS PROVIDED BY THE LICENSOR AND COPYRIGHT OWNER "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
* THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE LICENSOR OR COPYRIGHT
* OWNER BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
* EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
* PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
* PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY
* OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
* Image library configuration.
*/
#ifndef __IMLIB_CONFIG_H__
#define __IMLIB_CONFIG_H__
#if CORE_M55_HE
// Enable ISP ops
#define IMLIB_ENABLE_ISP_OPS
// Enable binary ops
#define IMLIB_ENABLE_BINARY_OPS
// Enable math ops
#define IMLIB_ENABLE_MATH_OPS
#else
// Enable Image I/O
#define IMLIB_ENABLE_IMAGE_IO
// Enable Image File I/O
#define IMLIB_ENABLE_IMAGE_FILE_IO
// Enable LAB LUT
#define IMLIB_ENABLE_LAB_LUT
// Enable YUV LUT
//#define IMLIB_ENABLE_YUV_LUT
// Enable mean pooling
#define IMLIB_ENABLE_MEAN_POOLING
// Enable midpoint pooling
#define IMLIB_ENABLE_MIDPOINT_POOLING
// Enable ISP ops
#define IMLIB_ENABLE_ISP_OPS
// Enable binary ops
#define IMLIB_ENABLE_BINARY_OPS
// Enable math ops
#define IMLIB_ENABLE_MATH_OPS
// Enable flood_fill()
#define IMLIB_ENABLE_FLOOD_FILL
// Enable mean()
#define IMLIB_ENABLE_MEAN
// Enable median()
#define IMLIB_ENABLE_MEDIAN
// Enable mode()
#define IMLIB_ENABLE_MODE
// Enable midpoint()
#define IMLIB_ENABLE_MIDPOINT
// Enable morph()
#define IMLIB_ENABLE_MORPH
// Enable Gaussian
#define IMLIB_ENABLE_GAUSSIAN
// Enable Laplacian
#define IMLIB_ENABLE_LAPLACIAN
// Enable bilateral()
#define IMLIB_ENABLE_BILATERAL
// Enable cartoon()
// #define IMLIB_ENABLE_CARTOON
// Enable linpolar()
#define IMLIB_ENABLE_LINPOLAR
// Enable logpolar()
#define IMLIB_ENABLE_LOGPOLAR
// Enable lens_corr()
#define IMLIB_ENABLE_LENS_CORR
// Enable rotation_corr()
#define IMLIB_ENABLE_ROTATION_CORR
// Enable phasecorrelate()
#if defined(IMLIB_ENABLE_ROTATION_CORR)
#define IMLIB_ENABLE_FIND_DISPLACEMENT
#endif
// Enable get_similarity()
#define IMLIB_ENABLE_GET_SIMILARITY
// Enable find_lines()
#define IMLIB_ENABLE_FIND_LINES
// Enable find_line_segments()
#define IMLIB_ENABLE_FIND_LINE_SEGMENTS
// Enable find_circles()
#define IMLIB_ENABLE_FIND_CIRCLES
// Enable find_rects()
#define IMLIB_ENABLE_FIND_RECTS
// Enable find_qrcodes() (14 KB)
#define IMLIB_ENABLE_QRCODES
// Enable find_apriltags() (64 KB)
#define IMLIB_ENABLE_APRILTAGS
#define IMLIB_ENABLE_APRILTAGS_TAG36H11
// Enable fine find_apriltags() - (8-way connectivity versus 4-way connectivity)
// #define IMLIB_ENABLE_FINE_APRILTAGS
// Enable high res find_apriltags() - uses more RAM
#define IMLIB_ENABLE_HIGH_RES_APRILTAGS
// Enable find_datamatrices() (26 KB)
#define IMLIB_ENABLE_DATAMATRICES
// Enable find_barcodes() (42 KB)
#define IMLIB_ENABLE_BARCODES
// Enable find_features()
#define IMLIB_ENABLE_FEATURES
// Enable FAST (20+ KBs).
// #define IMLIB_ENABLE_FAST
// Enable find_template()
#define IMLIB_FIND_TEMPLATE
// Enable find_lbp()
#define IMLIB_ENABLE_FIND_LBP
// Enable find_keypoints()
#define IMLIB_ENABLE_FIND_KEYPOINTS
// Enable load, save and match descriptor
#define IMLIB_ENABLE_DESCRIPTOR
// Enable find_hog()
// #define IMLIB_ENABLE_HOG
// Enable selective_search()
// #define IMLIB_ENABLE_SELECTIVE_SEARCH
// Enable PNG encoder/decoder
#define IMLIB_ENABLE_PNG_ENCODER
#define IMLIB_ENABLE_PNG_DECODER
// Stereo Imaging
// #define IMLIB_ENABLE_STEREO_DISPARITY
// Fast debayer
#define IMLIB_ENABLE_DEBAYER_OPTIMIZATION
#endif
#endif //__IMLIB_CONFIG_H__

View File

@ -0,0 +1,14 @@
static const char fresh_main_py[] =
"# main.py -- put your code here!\n"
"import machine, time\n"
"led = machine.LED(\"LED_BLUE\")\n"
"while (True):\n"
" led.on()\n"
" time.sleep_ms(150)\n"
" led.off()\n"
" time.sleep_ms(100)\n"
" led.on()\n"
" time.sleep_ms(150)\n"
" led.off()\n"
" time.sleep_ms(600)\n"
;

View File

@ -0,0 +1,36 @@
include("$(MPY_DIR)/extmod/asyncio")
# Drivers
require("lsm6dsox")
#freeze ("$(OMV_LIB_DIR)/", "modbus.py")
#freeze ("$(OMV_LIB_DIR)/", "pid.py")
#freeze ("$(OMV_LIB_DIR)/", "bno055.py")
#freeze ("$(OMV_LIB_DIR)/", "ssd1306.py")
#freeze ("$(OMV_LIB_DIR)/", "tb6612.py")
freeze ("$(OMV_LIB_DIR)/", "vl53l1x.py")
freeze ("$(OMV_LIB_DIR)/", "machine.py")
#freeze ("$(OMV_LIB_DIR)/", "display.py")
freeze ("$(OMV_LIB_DIR)/", "openamp.py")
freeze ("$(OMV_LIB_DIR)/ml")
freeze ("$(OMV_LIB_DIR)/", "romfs.py")
# Networking
require("ssl")
require("ntptime")
require("webrepl")
#freeze ("$(OMV_LIB_DIR)/", "rpc.py")
freeze ("$(OMV_LIB_DIR)/", "rtsp.py")
freeze ("$(OMV_LIB_DIR)/", "mqtt.py")
freeze ("$(OMV_LIB_DIR)/", "requests.py")
# Utils
require("time")
require("logging")
require("collections-defaultdict")
require("types")
# Bluetooth
require("aioble")
# Custom boot script.
freeze("$(OMV_LIB_DIR)/alif/$(MCU_CORE)", "_boot.py")

View File

@ -0,0 +1,289 @@
/*
* Copyright (C) 2023-2024 OpenMV, LLC.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Any redistribution, use, or modification in source or binary form
* is done solely for personal benefit and not for any commercial
* purpose or for monetary gain. For commercial licensing options,
* please contact openmv@openmv.io
*
* THIS SOFTWARE IS PROVIDED BY THE LICENSOR AND COPYRIGHT OWNER "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
* THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE LICENSOR OR COPYRIGHT
* OWNER BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
* EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
* PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
* PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY
* OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
* Board configuration and pin definitions.
*/
#ifndef __OMV_BOARDCONFIG_H__
#define __OMV_BOARDCONFIG_H__
// Architecture info
#define OMV_BOARD_ARCH "OPENMV AE3" // 33 chars max
#define OMV_BOARD_TYPE "AE3"
#ifndef LINKER_SCRIPT
void se_services_reset_soc(void);
extern unsigned char OMV_BOARD_UID_ADDR[12]; // Unique address.
#endif
#define OMV_BOARD_UID_SIZE 3 // Unique ID size in words.
#define OMV_BOARD_UID_OFFSET 4 // Bytes offset for multi-word UIDs.
#define OMV_BOARD_RESET se_services_reset_soc
// GPU configuration
#define OMV_GPU_ENABLE (CORE_M55_HP)
// JPEG configuration.
#define OMV_JPEG_CODEC_ENABLE (0)
#define OMV_JPEG_QUALITY_LOW (50)
#define OMV_JPEG_QUALITY_HIGH (68)
#define OMV_JPEG_QUALITY_THRESHOLD (320 * 240 * 2)
// Enable RAW preview.
#define OMV_RAW_PREVIEW_ENABLE (1)
#define OMV_RAW_PREVIEW_WIDTH (512)
#define OMV_RAW_PREVIEW_HEIGHT (320)
// CSI drivers configuration.
#define OMV_PAG7936_ENABLE (CORE_M55_HP)
// FIR drivers configuration.
#define OMV_FIR_MLX90621_ENABLE (0)
#define OMV_FIR_MLX90640_ENABLE (0)
#define OMV_FIR_MLX90641_ENABLE (0)
#define OMV_FIR_AMG8833_ENABLE (1)
#define OMV_FIR_LEPTON_ENABLE (0)
#define OMV_TOF_VL53L5CX_ENABLE (1)
// Debugging configuration.
#define OMV_TUSBDBG_ENABLE (CORE_M55_HP)
#define OMV_TUSBDBG_PACKET (512)
#define OMV_TUSBDBG_BUFFER (4096)
// UMM heap block size
#define OMV_UMM_BLOCK_SIZE 256
// USB config.
#define OMV_USB_IRQN (USB_IRQ_IRQn)
#define OMV_USB1_IRQ_HANDLER (USB_IRQHandler)
#define OMV_USB_SWITCH_PIN (&omv_pin_USB_SWITCH)
// Linker script constants (see the linker script template alif.ld.S).
// Note: fb_alloc is a stack-based, dynamically allocated memory on FB.
// The maximum available fb_alloc memory = FB_ALLOC_SIZE + FB_SIZE - (w*h*bpp).
#if BOOTLOADER
// Bootloader config
#define OMV_MAIN_MEMORY DTCM // data, bss and heap memory
#define OMV_HEAP_MEMORY DTCM // heap memory
#define OMV_HEAP_SIZE (256K)
#define OMV_STACK_MEMORY ITCM // stack memory
#define OMV_STACK_SIZE (256K)
#elif CORE_M55_HP
// HP core config
#define OMV_MAIN_MEMORY DTCM // data, bss
#define OMV_HEAP_MEMORY DTCM // libc/sbrk heap memory
#define OMV_HEAP_SIZE (128K)
#define OMV_BSS_SRAM_MEMORY SRAM1 // BSS memory outside DTCM.
#define OMV_STACK_MEMORY ITCM // stack memory
#define OMV_STACK_SIZE (256K)
#define OMV_FB_MEMORY SRAM1 // Main Frame buffer, fb_alloc
#define OMV_FB_SIZE (2048K)
#define OMV_FB_ALLOC_SIZE (464K) // Minimum fb alloc size
#define OMV_FB_OVERLAY_MEMORY DTCM // Fast fb_alloc memory.
#define OMV_FB_OVERLAY_SIZE (256K) // Fast fb_alloc memory size.
#define OMV_JPEG_MEMORY SRAM6_A // JPEG buffer.
#define OMV_JPEG_SIZE (1M)
#define OMV_DMA_MEMORY DTCM // Misc DMA buffers memory.
#define OMV_GPU_MEMORY SRAM9_B // GPU heap.
#define OMV_GPU_SIZE (256K)
#define OMV_OPENAMP_MEMORY SRAM9_A // Open-AMP SHM.
#define OMV_OPENAMP_SIZE (64K)
#define OMV_GC_BLOCK0_MEMORY SRAM0 // Extra GC block 1
#define OMV_GC_BLOCK0_SIZE (4M)
#else
// HE core config
#define OMV_MAIN_MEMORY DTCM // data, bss
#define OMV_HEAP_MEMORY DTCM // libc/sbrk heap memory
#define OMV_HEAP_SIZE (64K)
#define OMV_BSS_SRAM_MEMORY SRAM6_B // BSS memory outside DTCM.
#define OMV_STACK_MEMORY ITCM // stack memory
#define OMV_STACK_SIZE (256K)
#define OMV_FB_MEMORY SRAM6_B // Main Frame buffer, fb_alloc
#define OMV_FB_SIZE (256K)
#define OMV_FB_ALLOC_SIZE (256K) // Minimum fb alloc size
#define OMV_JPEG_MEMORY SRAM6_B // JPEG buffer.
#define OMV_JPEG_SIZE (500K)
#define OMV_DMA_MEMORY DTCM // Misc DMA buffers memory.
#define OMV_OPENAMP_MEMORY SRAM9_A // Open-AMP SHM
#define OMV_OPENAMP_SIZE (64K)
#define OMV_GC_BLOCK0_MEMORY SRAM8 // Main GC block
#define OMV_GC_BLOCK0_SIZE (2M)
#endif
// Flash configuration.
#if BOOTLOADER
#define OMV_FLASH_ORIGIN 0x80000000
#define OMV_FLASH_LENGTH 0x00020000 /* 128K */
#elif CORE_M55_HP
#define OMV_FLASH_ORIGIN 0x80020000
#define OMV_FLASH_LENGTH 0x00300000 /* 3MB */
#define OMV_ROMFS_PART0_ORIGIN 0xa1000000
#define OMV_ROMFS_PART0_LENGTH 0x01000000
#define OMV_ROMFS_PART1_ORIGIN 0x8047E000
#define OMV_ROMFS_PART1_LENGTH 0x00100000
#elif CORE_M55_HE
#define OMV_FLASH_ORIGIN 0x80320000
#define OMV_FLASH_LENGTH 0x0015E000 /* 1.4MB */
#define OMV_ROMFS_PART0_ORIGIN 0x8047E000
#define OMV_ROMFS_PART0_LENGTH 0x00100000
#else
#error "MCU core is not specified"
#endif
// Memory configuration.
// Note SRAM2, SRAM3, SRAM4, SRAM5 are TCMs. Each M55 core sees its own ITCM
// memory mapped at 0x00000000, and its DTCM mapped at 0x20000000.
// Since the TCM is accessible through the global address map it is possible
// to configure peripherals and DMAs to read/write data to/from the TCM.
#define OMV_DTCM_ORIGIN 0x20000000
#define OMV_ITCM_ORIGIN 0x00000000
#if CORE_M55_HP
#define OMV_DTCM_LENGTH 1024K
#define OMV_ITCM_LENGTH 256K
#else
#define OMV_DTCM_LENGTH 256K
#define OMV_ITCM_LENGTH 256K
#endif
#define OMV_SRAM0_ORIGIN 0x02000000
#define OMV_SRAM0_LENGTH 4096K
#define OMV_SRAM1_ORIGIN 0x08000000
#define OMV_SRAM1_LENGTH 2560K
// #define SRAM2_ORIGIN 0x50000000
// #define SRAM2_LENGTH 0x00040000 /* 256K */
// #define SRAM3_ORIGIN 0x50800000
// #define SRAM3_LENGTH 0x00100000 /* 1M */
// #define SRAM4_ORIGIN 0x58000000
// #define SRAM4_LENGTH 0x00040000 /* 256K */
// #define SRAM5_ORIGIN 0x58800000
// #define SRAM5_LENGTH 0x00040000 /* 256K */
#define OMV_SRAM6_A_ORIGIN 0x62000000
#define OMV_SRAM6_A_LENGTH 0x00100000 /* 1M */
#define OMV_SRAM6_B_ORIGIN 0x62400000
#define OMV_SRAM6_B_LENGTH 0x00100000 /* 1M */
#define OMV_SRAM7_ORIGIN 0x63000000
#define OMV_SRAM7_LENGTH 0x00080000 /* 512K */
#define OMV_SRAM8_ORIGIN 0x63200000
#define OMV_SRAM8_LENGTH 0x00200000 /* 2M */
#define OMV_SRAM9_A_ORIGIN 0x60000000
#define OMV_SRAM9_A_LENGTH 0x00040000 /* 256K */
#define OMV_SRAM9_B_ORIGIN 0x60040000
#define OMV_SRAM9_B_LENGTH 0x00080000 /* 512K */
// Physical I2C/I3C buses.
// I2C0
#define OMV_I2C0_ID (0)
#define OMV_I2C0_SCL_PIN (&omv_pin_I2C0_SCL)
#define OMV_I2C0_SDA_PIN (&omv_pin_I2C0_SDA)
// I2C1
#define OMV_I2C1_ID (1)
#define OMV_I2C1_SCL_PIN (&omv_pin_I2C1_SCL)
#define OMV_I2C1_SDA_PIN (&omv_pin_I2C1_SDA)
// I2C3
#define OMV_I2C3_ID (3)
#define OMV_I2C3_SCL_PIN (&omv_pin_I2C3_SCL)
#define OMV_I2C3_SDA_PIN (&omv_pin_I2C3_SDA)
// I3C0
#define OMV_I3C0_ID (4)
#define OMV_I3C0_SCL_PIN (&omv_pin_I3C_SCL)
#define OMV_I3C0_SDA_PIN (&omv_pin_I3C_SDA)
// Physical PDM buses.
// PDM1
#define OMV_PDM1_ID (1)
#define OMV_PDM1_C0_PIN (&omv_pin_PDM_C1)
#define OMV_PDM1_D0_PIN (&omv_pin_PDM_D1)
// Physical SPI buses.
// SPI bus 4
#define OMV_SPI4_ID (4)
#define OMV_SPI4_SCLK_PIN (&omv_pin_LPSPI_SCLK)
#define OMV_SPI4_MISO_PIN (&omv_pin_LPSPI_MISO)
#define OMV_SPI4_MOSI_PIN (&omv_pin_LPSPI_MOSI)
#define OMV_SPI4_SSEL_PIN (&omv_pin_LPSPI_SSEL)
// CSI I2C bus
#define OMV_CSI_I2C_ID (0)
#define OMV_CSI_I2C_SPEED (OMV_I2C_SPEED_FULL)
// FIR I2C bus
#define OMV_FIR_I2C_ID (1)
#define OMV_FIR_I2C_SPEED (OMV_I2C_SPEED_FULL)
// TOF I2C bus
#define OMV_TOF_I2C_ID (3)
#define OMV_TOF_I2C_SPEED (OMV_I2C_SPEED_FULL)
#define OMV_TOF_POWER_PIN (&omv_pin_TOF_POWER)
// IMU SPI bus
#define OMV_IMU_SPI_ID (OMV_SPI4_ID)
#define OMV_IMU_SPI_BAUDRATE (500000)
#define OMV_IMU_CHIP_LSM6DSM (1)
#define OMV_IMU_X_Y_ROTATION_DEGREES 90
#define OMV_IMU_MOUNTING_Z_DIRECTION -1
// PDM configuration
#define OMV_PDM_ID (OMV_PDM1_ID)
#define OMV_PDM_CHANNELS (1)
// Camera interface
#define OMV_CSI_BASE ((CPI_Type *) CPI_BASE)
#define OMV_CSI_CLK_FREQUENCY (12000000)
#define OMV_CSI_D0_PIN (&omv_pin_CSI_D0)
#define OMV_CSI_D1_PIN (&omv_pin_CSI_D1)
#define OMV_CSI_D2_PIN (&omv_pin_CSI_D2)
#define OMV_CSI_D3_PIN (&omv_pin_CSI_D3)
#define OMV_CSI_D4_PIN (&omv_pin_CSI_D4)
#define OMV_CSI_D5_PIN (&omv_pin_CSI_D5)
#define OMV_CSI_D6_PIN (&omv_pin_CSI_D6)
#define OMV_CSI_D7_PIN (&omv_pin_CSI_D7)
#define OMV_CSI_HSYNC_PIN (&omv_pin_CSI_HSYNC)
#define OMV_CSI_VSYNC_PIN (&omv_pin_CSI_VSYNC)
#define OMV_CSI_PXCLK_PIN (&omv_pin_CSI_PXCLK)
#define OMV_CSI_MXCLK_PIN (&omv_pin_CSI_MXCLK)
#define OMV_CSI_RESET_PIN (&omv_pin_CSI_RESET)
#define OMV_CSI_POWER_PIN (&omv_pin_CSI_POWER)
#define OMV_WL_POWER_PIN (&omv_pin_WL_REG_ON)
#define OMV_BT_POWER_PIN (&omv_pin_BT_REG_ON)
#endif //__OMV_BOARDCONFIG_H__

View File

@ -0,0 +1,28 @@
MCU_SERIES=E7
MCU_VARIANT=AE722F80F55D5XX
CPU=cortex-m55
FPU=fpv5-d16
FABI=hard
PORT=alif
HAL_DIR=hal/alif
PINS_AF_H='<alif_pins.h>'
ARM_MATH=ARM_MATH_HELIUM
OMV_BOOT_ADDR=0x80000000
OMV_FIRM_ADDR=0x80020000
OMV_HSE_VALUE=12000000
MICROPY_PY_CSI = $(CORE_M55_HP)
MICROPY_PY_ULAB = 1
MICROPY_PY_TOF = 1
MICROPY_PY_IMU = 1
MICROPY_PY_AUDIO = 1
MICROPY_PY_ML = 1
MICROPY_PY_ML_TFLM = 1
MICROPY_PY_NETWORK = $(CORE_M55_HP)
MICROPY_PY_BLUETOOTH = $(CORE_M55_HP)
MICROPY_BLUETOOTH_NIMBLE = $(CORE_M55_HP)
MICROPY_PY_LWIP = $(CORE_M55_HP)
MICROPY_PY_NETWORK_CYW43 = $(CORE_M55_HP)
MICROPY_PY_SSL = $(CORE_M55_HP)
MICROPY_SSL_MBEDTLS = $(CORE_M55_HP)
MICROPY_PY_OPENAMP = 1
MICROPY_PY_OPENAMP_REMOTEPROC = 1

View File

@ -0,0 +1,120 @@
/*
* Copyright (C) 2023-2024 OpenMV, LLC.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Any redistribution, use, or modification in source or binary form
* is done solely for personal benefit and not for any commercial
* purpose or for monetary gain. For commercial licensing options,
* please contact openmv@openmv.io
*
* THIS SOFTWARE IS PROVIDED BY THE LICENSOR AND COPYRIGHT OWNER "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
* THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE LICENSOR OR COPYRIGHT
* OWNER BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
* EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
* PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
* PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY
* OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
* Bootloader configuration.
*/
// *INDENT-OFF*
#ifndef __OMV_BOOTCONFIG_H__
#define __OMV_BOOTCONFIG_H__
#include ALIF_CMSIS_H
#include "port.h"
#include "gpio.h"
#include "pinconf.h"
// Misc config.
#define OMV_BOOT_VID (0x37C5)
#define OMV_BOOT_PID (0x96E3)
#define OMV_BOOT_DFU_TIMEOUT (1500)
#define OMV_BOOT_MAGIC_ADDR (0x200FFFFCU)
// Flash config.
#define OMV_BOOT_AXI_FLASH_ENABLE (1)
#define OMV_BOOT_SPI_FLASH_ENABLE (1)
#define OMV_BOOT_REC_FLASH_ENABLE (1)
// OSPI config.
#define OMV_BOOT_OSPI_SER (1)
#define OMV_BOOT_OSPI_RX_DELAY (4)
#define OMV_BOOT_OSPI_DDR_EDGE (0)
#define OMV_BOOT_OSPI_RXDS_DELAY (12)
#define OMV_BOOT_OSPI_CLOCK (50000000)
#define OMV_BOOT_OSPI_SSI_BASE (OSPI0_BASE)
#define OMV_BOOT_OSPI_AES_BASE (AES0_BASE)
#define OMV_BOOT_OSPI_XIP_BASE (OSPI0_XIP_BASE)
// IRQ priorities.
#define NVIC_PRIORITYGROUP_7 ((uint32_t)0x00000000U)
#define OMV_BOOT_TIM_IRQ_PRI NVIC_EncodePriority(NVIC_PRIORITYGROUP_7, 0, 0)
#define OMV_BOOT_USB_IRQ_PRI NVIC_EncodePriority(NVIC_PRIORITYGROUP_7, 5, 0)
// Board GPIO pins (NOTE: indices in the pins table)
#define OMV_BOOT_MUX_PIN (0)
#define OMV_BOOT_LED_PIN (1)
#define OMV_BOOT_OSPI_RST_PIN (2)
#define OMV_BOOT_OSPI_D0_PIN (3)
#define OMV_BOOT_OSPI_CS_PIN (13)
#define OMV_BOOT_PAD_IO (PADCTRL_OUTPUT_DRIVE_STRENGTH_12MA)
#define OMV_BOOT_PAD_Dx (PADCTRL_OUTPUT_DRIVE_STRENGTH_12MA | PADCTRL_SLEW_RATE_FAST | PADCTRL_READ_ENABLE)
#define OMV_BOOT_PAD_D2 (OMV_BOOT_PAD_Dx | PADCTRL_DRIVER_DISABLED_PULL_UP)
#define OMV_BOOT_PAD_Cx (PADCTRL_OUTPUT_DRIVE_STRENGTH_12MA | PADCTRL_SLEW_RATE_FAST)
#define OMV_BOOT_ALT_GPIO PINMUX_ALTERNATE_FUNCTION_0
#define OMV_BOOT_ALT_OSPI PINMUX_ALTERNATE_FUNCTION_1
#define ALIF_GPIO(x) ((GPIO_Type *) x##_BASE)
static const pin_t omv_boot_pins[] = {
{ .gpio = ALIF_GPIO(LPGPIO), .port = PORT_15, .pin = PIN_0, .alt = OMV_BOOT_ALT_GPIO, .pad = OMV_BOOT_PAD_IO }, /* MUX */
{ .gpio = ALIF_GPIO(GPIO6), .port = PORT_6, .pin = PIN_3, .alt = OMV_BOOT_ALT_GPIO, .pad = OMV_BOOT_PAD_IO }, /* LED */
{ .gpio = ALIF_GPIO(GPIO3), .port = PORT_3, .pin = PIN_3, .alt = OMV_BOOT_ALT_GPIO, .pad = OMV_BOOT_PAD_IO }, /* RST */
{ .gpio = ALIF_GPIO(GPIO2), .port = PORT_2, .pin = PIN_0, .alt = OMV_BOOT_ALT_OSPI, .pad = OMV_BOOT_PAD_Dx }, /* D0 */
{ .gpio = ALIF_GPIO(GPIO2), .port = PORT_2, .pin = PIN_1, .alt = OMV_BOOT_ALT_OSPI, .pad = OMV_BOOT_PAD_Dx }, /* D1 */
{ .gpio = ALIF_GPIO(GPIO2), .port = PORT_2, .pin = PIN_2, .alt = OMV_BOOT_ALT_OSPI, .pad = OMV_BOOT_PAD_D2 }, /* D2 */
{ .gpio = ALIF_GPIO(GPIO2), .port = PORT_2, .pin = PIN_3, .alt = OMV_BOOT_ALT_OSPI, .pad = OMV_BOOT_PAD_Dx }, /* D3 */
{ .gpio = ALIF_GPIO(GPIO2), .port = PORT_2, .pin = PIN_4, .alt = OMV_BOOT_ALT_OSPI, .pad = OMV_BOOT_PAD_Dx }, /* D4 */
{ .gpio = ALIF_GPIO(GPIO2), .port = PORT_2, .pin = PIN_5, .alt = OMV_BOOT_ALT_OSPI, .pad = OMV_BOOT_PAD_Dx }, /* D5 */
{ .gpio = ALIF_GPIO(GPIO2), .port = PORT_2, .pin = PIN_6, .alt = OMV_BOOT_ALT_OSPI, .pad = OMV_BOOT_PAD_Dx }, /* D6 */
{ .gpio = ALIF_GPIO(GPIO2), .port = PORT_2, .pin = PIN_7, .alt = OMV_BOOT_ALT_OSPI, .pad = OMV_BOOT_PAD_Dx }, /* D7 */
{ .gpio = ALIF_GPIO(GPIO1), .port = PORT_1, .pin = PIN_6, .alt = OMV_BOOT_ALT_OSPI, .pad = OMV_BOOT_PAD_Dx }, /* RXD */
{ .gpio = ALIF_GPIO(GPIO3), .port = PORT_3, .pin = PIN_0, .alt = OMV_BOOT_ALT_OSPI, .pad = OMV_BOOT_PAD_Cx }, /* CK */
{ .gpio = ALIF_GPIO(GPIO3), .port = PORT_3, .pin = PIN_2, .alt = OMV_BOOT_ALT_OSPI, .pad = OMV_BOOT_PAD_Cx }, /* CS */
};
#define OMV_BOOT_PINS_COUNT (sizeof(omv_boot_pins) / sizeof(omv_boot_pins[0]))
// Note the first MPU regions are used by startup code.
static const partition_t OMV_BOOT_DFU_PARTITIONS[] = {
{ .type = PTYPE_AXI_FLASH, .region= 4, .rdonly = 1, .start = 0x80000000, .limit = 0x80020000, .attr = MEMATTR_NORMAL_RA },
{ .type = PTYPE_AXI_FLASH, .region= 5, .rdonly = 0, .start = 0x80020000, .limit = 0x80320000, .attr = MEMATTR_DEVICE_nGnRE },
{ .type = PTYPE_AXI_FLASH, .region= 6, .rdonly = 0, .start = 0x80320000, .limit = 0x8047E000, .attr = MEMATTR_DEVICE_nGnRE },
{ .type = PTYPE_AXI_FLASH, .region= 7, .rdonly = 0, .start = 0x8047E000, .limit = 0x8057E000, .attr = MEMATTR_DEVICE_nGnRE },
{ .type = PTYPE_AXI_FLASH, .region= 8, .rdonly = 0, .start = 0x8057E000, .limit = 0x80580000, .attr = MEMATTR_DEVICE_nGnRE },
{ .type = PTYPE_SPI_FLASH, .region=-1, .rdonly = 0, .start = 0x00000000, .limit = 0x01000000, .attr = 0 },
{ .type = PTYPE_SPI_FLASH, .region=-1, .rdonly = 0, .start = 0x01000000, .limit = 0x02000000, .attr = 0 },
{ .type = PTYPE_REC_FLASH, .region=-1, .rdonly = 0, .start = 0x00000000, .limit = 0x00001000, .attr = 0 },
};
#define OMV_BOOT_DFU_PARTITIONS_COUNT 8 // Must be a literal
#define OMV_BOOT_DFU_PARTITIONS_STR "BOOT", "HP", "HE", "ROMFS0", "TOC", "RWFS", "ROMFS1", "RECOVERY"
// Protects MRAM before jump to main firmware
static const partition_t OMV_BOOT_XIP_PARTITIONS[] = {
{ .type = PTYPE_XIP_FLASH, .region= 4, .rdonly = 1, .start = 0x80000000, .limit = 0x80580000, .attr = MEMATTR_NORMAL_RA },
};
#define OMV_BOOT_XIP_PARTITIONS_COUNT (sizeof(OMV_BOOT_XIP_PARTITIONS) / sizeof(OMV_BOOT_XIP_PARTITIONS[0]))
#endif // __OMV_BOOTCONFIG_H__

View File

@ -0,0 +1,46 @@
// Pin Name, Port Number, Pin Number, AF, Input ON bit.
OMV_GPIO_DEFINE(I2C0_SDA, PORT_3, PIN_5, I2C0_SDA, true)
OMV_GPIO_DEFINE(I2C0_SCL, PORT_3, PIN_4, I2C0_SCL, true)
OMV_GPIO_DEFINE(I2C1_SDA, PORT_0, PIN_4, I2C1_SDA, true)
OMV_GPIO_DEFINE(I2C1_SCL, PORT_0, PIN_5, I2C1_SCL, true)
OMV_GPIO_DEFINE(I2C2_SDA, PORT_5, PIN_0, I2C2_SDA, true)
OMV_GPIO_DEFINE(I2C2_SCL, PORT_5, PIN_1, I2C2_SCL, true)
OMV_GPIO_DEFINE(I2C3_SDA, PORT_1, PIN_0, I2C3_SDA, true)
OMV_GPIO_DEFINE(I2C3_SCL, PORT_1, PIN_1, I2C3_SCL, true)
OMV_GPIO_DEFINE(I3C_SDA, PORT_1, PIN_2, I3C_SDA, true)
OMV_GPIO_DEFINE(I3C_SCL, PORT_1, PIN_3, I3C_SCL, true)
// MIC
OMV_GPIO_DEFINE(PDM_D1, PORT_3, PIN_7, LPPDM_D1, true)
OMV_GPIO_DEFINE(PDM_C1, PORT_3, PIN_6, LPPDM_C1, false)
OMV_GPIO_DEFINE(USB_SWITCH, PORT_15, PIN_0, GPIO, false)
OMV_GPIO_DEFINE(TOF_POWER, PORT_5, PIN_6, GPIO, false)
OMV_GPIO_DEFINE(CSI_D0, PORT_8, PIN_0, CAM_D0, true)
OMV_GPIO_DEFINE(CSI_D1, PORT_8, PIN_1, CAM_D1, true)
OMV_GPIO_DEFINE(CSI_D2, PORT_8, PIN_2, CAM_D2, true)
OMV_GPIO_DEFINE(CSI_D3, PORT_8, PIN_3, CAM_D3, true)
OMV_GPIO_DEFINE(CSI_D4, PORT_8, PIN_4, CAM_D4, true)
OMV_GPIO_DEFINE(CSI_D5, PORT_8, PIN_5, CAM_D5, true)
OMV_GPIO_DEFINE(CSI_D6, PORT_8, PIN_6, CAM_D6, true)
OMV_GPIO_DEFINE(CSI_D7, PORT_8, PIN_7, CAM_D7, true)
OMV_GPIO_DEFINE(CSI_HSYNC, PORT_10, PIN_0, CAM_HSYNC, true)
OMV_GPIO_DEFINE(CSI_VSYNC, PORT_10, PIN_1, CAM_VSYNC, true)
OMV_GPIO_DEFINE(CSI_PXCLK, PORT_10, PIN_2, CAM_PCLK, true)
OMV_GPIO_DEFINE(CSI_MXCLK, PORT_10, PIN_3, CAM_XVCLK, false)
OMV_GPIO_DEFINE(CSI_POWER, PORT_4, PIN_0, GPIO, false)
OMV_GPIO_DEFINE(CSI_RESET, PORT_4, PIN_1, GPIO, false)
// IMU
OMV_GPIO_DEFINE(LPSPI_MISO, PORT_11, PIN_4, LPSPI_MISO, true)
OMV_GPIO_DEFINE(LPSPI_MOSI, PORT_11, PIN_5, LPSPI_MOSI, true)
OMV_GPIO_DEFINE(LPSPI_SCLK, PORT_11, PIN_6, LPSPI_SCLK, true)
OMV_GPIO_DEFINE(LPSPI_SSEL, PORT_11, PIN_7, LPSPI_SS, true)
OMV_GPIO_DEFINE(BT_REG_ON, PORT_5, PIN_7, GPIO, false)
OMV_GPIO_DEFINE(WL_REG_ON, PORT_10, PIN_4, GPIO, false)

View File

@ -0,0 +1,80 @@
{
"0": {
"size": "0x100000",
"entries": [
{
"type": "tflite",
"path": "{TOP}/lib/tflm/models/micro_speech.tflite",
"alignment": 16,
"optimize": "Performance"
},
{
"type": "tflite",
"path": "{TOP}/lib/tflm/models/audio_preprocessor.tflite",
"optimize": "Performance"
},
{
"type": "tflite",
"path": "{TOP}/lib/tflm/models/force_int_quant.tflite",
"alignment": 16,
"optimize": "Performance"
}
]
},
"1": {
"size": "0x1000000",
"entries": [
{
"type": "tflite",
"path": "{TOP}/lib/tflm/models/micro_speech.tflite",
"alignment": 16,
"optimize": "Performance"
},
{
"type": "tflite",
"path": "{TOP}/lib/tflm/models/audio_preprocessor.tflite",
"alignment": 16,
"optimize": "Performance"
},
{
"type": "tflite",
"path": "{TOP}/lib/tflm/models/fomo_face_detection.tflite",
"alignment": 16,
"optimize": "Performance"
},
{
"type": "tflite",
"path": "{TOP}/lib/tflm/models/yolo_v5_224_nano.tflite",
"alignment": 16,
"optimize": "Performance"
},
{
"type": "tflite",
"path": "{TOP}/lib/tflm/models/person_detect.tflite",
"alignment": 16,
"optimize": "Performance"
},
{
"type": "tflite",
"path": "{TOP}/lib/tflm/models/force_int_quant.tflite",
"alignment": 16,
"optimize": "Performance"
},
{
"type": "haar",
"path": "{TOP}/lib/haar/haarcascade_eye.xml",
"stages": 0
},
{
"type": "haar",
"path": "{TOP}/lib/haar/haarcascade_smile.xml",
"stages": 0
},
{
"type": "haar",
"path": "{TOP}/lib/haar/haarcascade_frontalface.xml",
"stages": 0
}
]
}
}

View File

@ -0,0 +1,40 @@
/*
* Copyright (C) 2023-2024 OpenMV, LLC.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Any redistribution, use, or modification in source or binary form
* is done solely for personal benefit and not for any commercial
* purpose or for monetary gain. For commercial licensing options,
* please contact openmv@openmv.io
*
* THIS SOFTWARE IS PROVIDED BY THE LICENSOR AND COPYRIGHT OWNER "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
* THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE LICENSOR OR COPYRIGHT
* OWNER BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
* EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
* PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
* PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY
* OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
* Ulab config file.
*/
#ifndef __ULAB_CONFIG_H__
#define __ULAB_CONFIG_H__
// Override ulab defaults here.
#define ULAB_MAX_DIMS (4)
#define ULAB_SUPPORTS_COMPLEX (0)
#define ULAB_SCIPY_HAS_OPTIMIZE_MODULE (1)
#define ULAB_FFT_IS_NUMPY_COMPATIBLE (0)
#endif //__ULAB_CONFIG_H__