From 6505b566356710ab8a2715ebcfbafa5c50650c2d Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 17 Jun 2024 11:24:55 +0300 Subject: [PATCH 001/143] Create hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 1 + 1 file changed, 1 insertion(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat new file mode 100644 index 0000000000000..bca70f35318f3 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -0,0 +1 @@ +q From a3efb95a7e3634a17d77367f9388e4015ebe1e99 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 17 Jun 2024 11:26:53 +0300 Subject: [PATCH 002/143] Update hwdef.dat --- .../hwdef/Inferno-PMU/hwdef.dat | 133 +++++++++++++++++- 1 file changed, 132 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index bca70f35318f3..2afa67aaff07d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -1 +1,132 @@ -q +# hw definition file for processing by chibios_pins.py + +# Inferno-PMU Firmware + +# MCU class and specific type +MCU STM32F4xx STM32F412Rx + +# bootloader starts firmware at 64k +FLASH_RESERVE_START_KB 64 + +# store parameters in pages 2 and 3 +define STORAGE_FLASH_PAGE 2 +define HAL_STORAGE_SIZE 8192 + +# board ID for firmware load +APJ_BOARD_ID 1055 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +STM32_ST_USE_TIMER 5 + +# enable watchdog +define HAL_WATCHDOG_ENABLED_DEFAULT true + +# crystal frequency +OSCILLATOR_HZ 16000000 + +define CH_CFG_ST_FREQUENCY 1000000 + +# Flash available +FLASH_SIZE_KB 1024 + +STDOUT_SERIAL SD1 +STDOUT_BAUDRATE 57600 + +# order of UARTs +SERIAL_ORDER USART1 EMPTY EMPTY USART2 + +# USART1 for debug +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 +define DEFAULT_SERIAL0_BAUD 57600 + +# Enable the sensor voltage pin +PC13 VDD_3V3_SENSORS_EN OUTPUT HIGH + +# USART2 for GPS +PA2 USART2_TX USART2 SPEED_HIGH +PA3 USART2_RX USART2 SPEED_HIGH + +# SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI sensors +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# SPI CS +PB12 MAG_CS CS +PA8 BARO_CS CS + +# Baro probe +SPIDEV dps310 SPI1 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ +BARO DPS310 SPI:dps310 + +# Mag probe +SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ +COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180 +define AP_RM3100_REVERSAL_MASK 7 + +# PWM, WS2812 LED +PB8 TIM4_CH3 TIM4 PWM(1) GPIO(50) +PB9 TIM4_CH4 TIM4 PWM(2) GPIO(51) +PA15 TIM2_CH1 TIM2 PWM(3) GPIO(52) +PB4 TIM3_CH1 TIM3 PWM(4) GPIO(53) + +define HAL_USE_ADC TRUE +define STM32_ADC_USE_ADC1 TRUE +#define HAL_DISABLE_ADC_DRIVER TRUE +PA0 VSENSE ADC1 SCALE(2) + +define HAL_NO_GPIO_IRQ + +# avoid RCIN thread to save memory +define HAL_USE_RTC FALSE +define DMA_RESERVE_SIZE 0 + +# enable CAN support +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 + +# use DNA +define HAL_CAN_DEFAULT_NODE_ID 0 + +define HAL_NO_MONITOR_THREAD +define HAL_DEVICE_THREAD_STACK 768 + +# disable dual GPS and GPS blending to save flash space +define GPS_MAX_RECEIVERS 1 +define GPS_MAX_INSTANCES 1 +define HAL_COMPASS_MAX_SENSORS 1 + +# GPS+MAG+BARO+Buzzer+NeoPixels +define HAL_PERIPH_ENABLE_GPS +define HAL_PERIPH_GPS_PORT_DEFAULT 3 +define HAL_PERIPH_ENABLE_MAG +define HAL_PERIPH_ENABLE_BARO +define HAL_PERIPH_ENABLE_RC_OUT +define HAL_PERIPH_ENABLE_NOTIFY + +# reserve 256 bytes for comms between app and bootloader +RAM_RESERVE_START 256 + +# allow for reboot command for faster development +define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 + +# we setup a small defaults.parm +define AP_PARAM_MAX_EMBEDDED_PARAM 256 + +#GPS M9N +PC11 M9EXTINT INPUT +PC10 M9RST INPUT +PC8 GPS_PPS_IN INPUT +PC7 M9SB INPUT + +define DEFAULT_NTF_LED_TYPES 455 + +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 From 4f7b65091b09558e27139245a7aa29c537f1f0c5 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 17 Jun 2024 11:27:54 +0300 Subject: [PATCH 003/143] Update hwdef.dat --- .../hwdef/Inferno-PMU/hwdef.dat | 167 +++++------------- 1 file changed, 48 insertions(+), 119 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 2afa67aaff07d..37490ef7c6164 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -1,132 +1,61 @@ -# hw definition file for processing by chibios_pins.py +include ../Inferno-PMU/hwdef.inc -# Inferno-PMU Firmware +# SERIAL +SERIAL_ORDER USART1 EMPTY USART3 -# MCU class and specific type -MCU STM32F4xx STM32F412Rx +# ESC +PB10 USART3_TX USART3 SPEED_HIGH +PB11 USART3_RX USART3 SPEED_HIGH -# bootloader starts firmware at 64k -FLASH_RESERVE_START_KB 64 +# USART2 +#PA2 USART2_TX USART2 SPEED_HIGH +#PA3 USART2_RX USART2 SPEED_HIGH -# store parameters in pages 2 and 3 -define STORAGE_FLASH_PAGE 2 -define HAL_STORAGE_SIZE 8192 +# DEBUG +PB6 USART1_TX USART1 SPEED_HIGH +PB7 USART1_RX USART1 SPEED_HIGH -# board ID for firmware load -APJ_BOARD_ID 1055 - -# setup build for a peripheral firmware -env AP_PERIPH 1 - -STM32_ST_USE_TIMER 5 - -# enable watchdog -define HAL_WATCHDOG_ENABLED_DEFAULT true - -# crystal frequency -OSCILLATOR_HZ 16000000 - -define CH_CFG_ST_FREQUENCY 1000000 - -# Flash available -FLASH_SIZE_KB 1024 - -STDOUT_SERIAL SD1 -STDOUT_BAUDRATE 57600 - -# order of UARTs -SERIAL_ORDER USART1 EMPTY EMPTY USART2 - -# USART1 for debug -PA9 USART1_TX USART1 -PA10 USART1_RX USART1 -define DEFAULT_SERIAL0_BAUD 57600 - -# Enable the sensor voltage pin -PC13 VDD_3V3_SENSORS_EN OUTPUT HIGH - -# USART2 for GPS -PA2 USART2_TX USART2 SPEED_HIGH -PA3 USART2_RX USART2 SPEED_HIGH - -# SWD debugging -PA13 JTMS-SWDIO SWD -PA14 JTCK-SWCLK SWD - -# SPI sensors -PA5 SPI1_SCK SPI1 -PA6 SPI1_MISO SPI1 -PA7 SPI1_MOSI SPI1 - -# SPI CS -PB12 MAG_CS CS -PA8 BARO_CS CS - -# Baro probe -SPIDEV dps310 SPI1 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ -BARO DPS310 SPI:dps310 - -# Mag probe -SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ -COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180 -define AP_RM3100_REVERSAL_MASK 7 - -# PWM, WS2812 LED -PB8 TIM4_CH3 TIM4 PWM(1) GPIO(50) -PB9 TIM4_CH4 TIM4 PWM(2) GPIO(51) -PA15 TIM2_CH1 TIM2 PWM(3) GPIO(52) -PB4 TIM3_CH1 TIM3 PWM(4) GPIO(53) +# BATTERY +define HAL_PERIPH_ENABLE_BATTERY define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE -#define HAL_DISABLE_ADC_DRIVER TRUE -PA0 VSENSE ADC1 SCALE(2) - -define HAL_NO_GPIO_IRQ - -# avoid RCIN thread to save memory -define HAL_USE_RTC FALSE -define DMA_RESERVE_SIZE 0 - -# enable CAN support -PA11 CAN1_RX CAN1 -PA12 CAN1_TX CAN1 - -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 -define HAL_NO_MONITOR_THREAD -define HAL_DEVICE_THREAD_STACK 768 +PB0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PB1 BATT_CURRENT_SENS ADC1 SCALE(1) + +define HAL_BATT_MONITOR_DEFAULT 0 +define HAL_BATT_VOLT_PIN 5 +define HAL_BATT_VOLT_SCALE 21.0 +define HAL_BATT_CURR_PIN 6 +define HAL_BATT_CURR_SCALE 40.0 + +#PWM +PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50) +PA9 TIM1_CH2 TIM1 PWM(2) GPIO(51) +PA10 TIM1_CH3 TIM1 PWM(3) GPIO(52) +PA11 TIM1_CH4 TIM1 PWM(4) GPIO(53) +PA15 TIM2_CH1 TIM2 PWM(5) GPIO(54) +PA2 TIM2_CH3 TIM2 PWM(6) GPIO(55) +PA3 TIM2_CH4 TIM2 PWM(7) GPIO(56) +PA1 TIM2_CH2 TIM2 PWM(8) GPIO(57) +PA6 TIM16_CH1 TIM16 PWM(9) GPIO(58) NODMA -# disable dual GPS and GPS blending to save flash space -define GPS_MAX_RECEIVERS 1 -define GPS_MAX_INSTANCES 1 -define HAL_COMPASS_MAX_SENSORS 1 - -# GPS+MAG+BARO+Buzzer+NeoPixels -define HAL_PERIPH_ENABLE_GPS -define HAL_PERIPH_GPS_PORT_DEFAULT 3 -define HAL_PERIPH_ENABLE_MAG -define HAL_PERIPH_ENABLE_BARO define HAL_PERIPH_ENABLE_RC_OUT define HAL_PERIPH_ENABLE_NOTIFY -# reserve 256 bytes for comms between app and bootloader -RAM_RESERVE_START 256 - -# allow for reboot command for faster development -define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 - -# we setup a small defaults.parm -define AP_PARAM_MAX_EMBEDDED_PARAM 256 - -#GPS M9N -PC11 M9EXTINT INPUT -PC10 M9RST INPUT -PC8 GPS_PPS_IN INPUT -PC7 M9SB INPUT - -define DEFAULT_NTF_LED_TYPES 455 - -# bootloader embedding / bootloader flashing not available -define AP_BOOTLOADER_FLASHING_ENABLED 0 +# enable ESC control +define HAL_SUPPORT_RCOUT_SERIAL 1 +define HAL_WITH_ESC_TELEM 1 + +#GPIO LED +define HAL_HAVE_PIXRACER_LED +PB2 LED_RED OUTPUT OPENDRAIN HIGH GPIO(0) +PB4 LED_GREEN OUTPUT OPENDRAIN LOW GPIO(1) +PB5 LED_BLUE OUTPUT OPENDRAIN LOW GPIO(2) +define HAL_GPIO_A_LED_PIN 0 +define HAL_GPIO_B_LED_PIN 1 +define HAL_GPIO_C_LED_PIN 2 + +define HAL_SERIAL_ESC_COMM_ENABLED 1 +define HAL_RCIN_THREAD_ENABLED 1 From ccc1b9305c03c90e4c06de77ba184ac953603883 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 17 Jun 2024 11:28:43 +0300 Subject: [PATCH 004/143] Create hwdef.inc --- .../hwdef/Inferno-PMU/hwdef.inc | 64 +++++++++++++++++++ 1 file changed, 64 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.inc new file mode 100644 index 0000000000000..726c65dd54874 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.inc @@ -0,0 +1,64 @@ +# MCU class and specific type +MCU STM32L431 STM32L431xx + +# bootloader starts firmware at 36k + 4k (STORAGE_FLASH) +FLASH_RESERVE_START_KB 40 +FLASH_SIZE_KB 256 + +# store parameters in pages 18 and 19 +STORAGE_FLASH_PAGE 18 +define HAL_STORAGE_SIZE 800 + +# ChibiOS system timer +STM32_ST_USE_TIMER 15 +define CH_CFG_ST_RESOLUTION 16 + +# board ID for firmware load +APJ_BOARD_ID 1080 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +env AP_PERIPH 1 + +STDOUT_SERIAL SD1 +STDOUT_BAUDRATE 57600 + +define HAL_NO_GPIO_IRQ +define SERIAL_BUFFERS_SIZE 512 +define PORT_INT_REQUIRED_STACK 64 + +define DMA_RESERVE_SIZE 0 + +# MAIN_STACK is stack for ISR handlers +MAIN_STACK 0x300 + +# PROCESS_STACK controls stack for main thread +PROCESS_STACK 0xA00 + +define HAL_NO_MONITOR_THREAD + +# setup a small defaults.parm +define AP_PARAM_MAX_EMBEDDED_PARAM 512 + +#ACT LED +PB3 LED OUTPUT HIGH +define HAL_LED_ON 1 + +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +#CAN bus +CAN_ORDER 1 +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 + +define HAL_CAN_POOL_SIZE 6000 + +# allow for reboot command for faster development +define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 + +# keep ROMFS uncompressed as we don't have enough RAM +# to uncompress the bootloader at runtime +env ROMFS_UNCOMPRESSED True From ac4b7b97c17942b37be66166cd6f727b7dd0e66a Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 17 Jun 2024 11:29:16 +0300 Subject: [PATCH 005/143] Update hwdef.inc --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.inc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.inc index 726c65dd54874..0b521cd023f9a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.inc @@ -1,5 +1,5 @@ # MCU class and specific type -MCU STM32L431 STM32L431xx +MCU STM32F412 STM32F412Rxx # bootloader starts firmware at 36k + 4k (STORAGE_FLASH) FLASH_RESERVE_START_KB 40 From dbf5dcb05ecc7f909c6525999bb4fda40589a99a Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 17 Jun 2024 11:38:46 +0300 Subject: [PATCH 006/143] Update hwdef.inc --- .../hwdef/Inferno-PMU/hwdef.inc | 134 +++++++++++++----- 1 file changed, 98 insertions(+), 36 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.inc index 0b521cd023f9a..7dbbc3a360593 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.inc @@ -1,64 +1,126 @@ # MCU class and specific type -MCU STM32F412 STM32F412Rxx +MCU STM32F4xx STM32F412Rx -# bootloader starts firmware at 36k + 4k (STORAGE_FLASH) -FLASH_RESERVE_START_KB 40 -FLASH_SIZE_KB 256 +# bootloader starts firmware at 64k +FLASH_RESERVE_START_KB 64 -# store parameters in pages 18 and 19 -STORAGE_FLASH_PAGE 18 -define HAL_STORAGE_SIZE 800 +# store parameters in pages 2 and 3 +define STORAGE_FLASH_PAGE 2 +define HAL_STORAGE_SIZE 8192 + +# setup build for a peripheral firmware +env AP_PERIPH 1 # ChibiOS system timer -STM32_ST_USE_TIMER 15 -define CH_CFG_ST_RESOLUTION 16 +STM32_ST_USE_TIMER 5 # board ID for firmware load -APJ_BOARD_ID 1080 +#APJ_BOARD_ID 1080 # crystal frequency -OSCILLATOR_HZ 8000000 +OSCILLATOR_HZ 16000000 -env AP_PERIPH 1 +define CH_CFG_ST_FREQUENCY 1000000 + +# Flash available +FLASH_SIZE_KB 1024 STDOUT_SERIAL SD1 STDOUT_BAUDRATE 57600 +# order of UARTs +SERIAL_ORDER USART1 EMPTY EMPTY USART2 + +# USART1 for debug +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 +define DEFAULT_SERIAL0_BAUD 57600 + +# Enable the sensor voltage pin +PC13 VDD_3V3_SENSORS_EN OUTPUT HIGH + +# USART2 for GPS +PA2 USART2_TX USART2 SPEED_HIGH +PA3 USART2_RX USART2 SPEED_HIGH + +# SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI sensors +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# SPI CS +PB12 MAG_CS CS +PA8 BARO_CS CS + +# Baro probe +SPIDEV dps310 SPI1 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ +BARO DPS310 SPI:dps310 + +# Mag probe +SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ +COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180 +define AP_RM3100_REVERSAL_MASK 7 + +# PWM, WS2812 LED +PB8 TIM4_CH3 TIM4 PWM(1) GPIO(50) +PB9 TIM4_CH4 TIM4 PWM(2) GPIO(51) +PA15 TIM2_CH1 TIM2 PWM(3) GPIO(52) +PB4 TIM3_CH1 TIM3 PWM(4) GPIO(53) + +define HAL_USE_ADC TRUE +define STM32_ADC_USE_ADC1 TRUE +#define HAL_DISABLE_ADC_DRIVER TRUE +PA0 VSENSE ADC1 SCALE(2) + define HAL_NO_GPIO_IRQ -define SERIAL_BUFFERS_SIZE 512 -define PORT_INT_REQUIRED_STACK 64 +# avoid RCIN thread to save memory +define HAL_USE_RTC FALSE define DMA_RESERVE_SIZE 0 -# MAIN_STACK is stack for ISR handlers -MAIN_STACK 0x300 +# enable CAN support +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 -# PROCESS_STACK controls stack for main thread -PROCESS_STACK 0xA00 +# use DNA +define HAL_CAN_DEFAULT_NODE_ID 0 define HAL_NO_MONITOR_THREAD +define HAL_DEVICE_THREAD_STACK 768 -# setup a small defaults.parm -define AP_PARAM_MAX_EMBEDDED_PARAM 512 - -#ACT LED -PB3 LED OUTPUT HIGH -define HAL_LED_ON 1 +# disable dual GPS and GPS blending to save flash space +define GPS_MAX_RECEIVERS 1 +define GPS_MAX_INSTANCES 1 +define HAL_COMPASS_MAX_SENSORS 1 -# debugger support -PA13 JTMS-SWDIO SWD -PA14 JTCK-SWCLK SWD - -#CAN bus -CAN_ORDER 1 -PB8 CAN1_RX CAN1 -PB9 CAN1_TX CAN1 +# GPS+MAG+BARO+Buzzer+NeoPixels +define HAL_PERIPH_ENABLE_GPS +define HAL_PERIPH_GPS_PORT_DEFAULT 3 +define HAL_PERIPH_ENABLE_MAG +define HAL_PERIPH_ENABLE_BARO +define HAL_PERIPH_ENABLE_RC_OUT +define HAL_PERIPH_ENABLE_NOTIFY -define HAL_CAN_POOL_SIZE 6000 +# reserve 256 bytes for comms between app and bootloader +RAM_RESERVE_START 256 # allow for reboot command for faster development define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 -# keep ROMFS uncompressed as we don't have enough RAM -# to uncompress the bootloader at runtime -env ROMFS_UNCOMPRESSED True +# we setup a small defaults.parm +define AP_PARAM_MAX_EMBEDDED_PARAM 256 + +#GPS M9N +PC11 M9EXTINT INPUT +PC10 M9RST INPUT +PC8 GPS_PPS_IN INPUT +PC7 M9SB INPUT + +define DEFAULT_NTF_LED_TYPES 455 + +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 From e70558fd9429d8c02ba7517f7eb59b8604954b4a Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 17 Jun 2024 11:40:41 +0300 Subject: [PATCH 007/143] Delete libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat --- .../hwdef/Inferno-PMU/hwdef.dat | 61 ------------------- 1 file changed, 61 deletions(-) delete mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat deleted file mode 100644 index 37490ef7c6164..0000000000000 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ /dev/null @@ -1,61 +0,0 @@ -include ../Inferno-PMU/hwdef.inc - -# SERIAL -SERIAL_ORDER USART1 EMPTY USART3 - -# ESC -PB10 USART3_TX USART3 SPEED_HIGH -PB11 USART3_RX USART3 SPEED_HIGH - -# USART2 -#PA2 USART2_TX USART2 SPEED_HIGH -#PA3 USART2_RX USART2 SPEED_HIGH - -# DEBUG -PB6 USART1_TX USART1 SPEED_HIGH -PB7 USART1_RX USART1 SPEED_HIGH - -# BATTERY -define HAL_PERIPH_ENABLE_BATTERY - -define HAL_USE_ADC TRUE -define STM32_ADC_USE_ADC1 TRUE - -PB0 BATT_VOLTAGE_SENS ADC1 SCALE(1) -PB1 BATT_CURRENT_SENS ADC1 SCALE(1) - -define HAL_BATT_MONITOR_DEFAULT 0 -define HAL_BATT_VOLT_PIN 5 -define HAL_BATT_VOLT_SCALE 21.0 -define HAL_BATT_CURR_PIN 6 -define HAL_BATT_CURR_SCALE 40.0 - -#PWM -PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50) -PA9 TIM1_CH2 TIM1 PWM(2) GPIO(51) -PA10 TIM1_CH3 TIM1 PWM(3) GPIO(52) -PA11 TIM1_CH4 TIM1 PWM(4) GPIO(53) -PA15 TIM2_CH1 TIM2 PWM(5) GPIO(54) -PA2 TIM2_CH3 TIM2 PWM(6) GPIO(55) -PA3 TIM2_CH4 TIM2 PWM(7) GPIO(56) -PA1 TIM2_CH2 TIM2 PWM(8) GPIO(57) -PA6 TIM16_CH1 TIM16 PWM(9) GPIO(58) NODMA - -define HAL_PERIPH_ENABLE_RC_OUT -define HAL_PERIPH_ENABLE_NOTIFY - -# enable ESC control -define HAL_SUPPORT_RCOUT_SERIAL 1 -define HAL_WITH_ESC_TELEM 1 - -#GPIO LED -define HAL_HAVE_PIXRACER_LED -PB2 LED_RED OUTPUT OPENDRAIN HIGH GPIO(0) -PB4 LED_GREEN OUTPUT OPENDRAIN LOW GPIO(1) -PB5 LED_BLUE OUTPUT OPENDRAIN LOW GPIO(2) -define HAL_GPIO_A_LED_PIN 0 -define HAL_GPIO_B_LED_PIN 1 -define HAL_GPIO_C_LED_PIN 2 - -define HAL_SERIAL_ESC_COMM_ENABLED 1 -define HAL_RCIN_THREAD_ENABLED 1 From 5d101221867ddf21b3b48e33fef7f46cd975c547 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 17 Jun 2024 11:51:47 +0300 Subject: [PATCH 008/143] Rename hwdef.inc to hwdef.dat --- .../AP_HAL_ChibiOS/hwdef/Inferno-PMU/{hwdef.inc => hwdef.dat} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/{hwdef.inc => hwdef.dat} (100%) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat similarity index 100% rename from libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.inc rename to libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat From 8679217f6dace996a14607a11ff4a1f56675e91c Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 17 Jun 2024 13:02:18 +0300 Subject: [PATCH 009/143] Update hwdef.dat --- .../hwdef/Inferno-PMU/hwdef.dat | 154 +++++++++--------- 1 file changed, 78 insertions(+), 76 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 7dbbc3a360593..a08854f9cfb8d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -28,99 +28,101 @@ FLASH_SIZE_KB 1024 STDOUT_SERIAL SD1 STDOUT_BAUDRATE 57600 -# order of UARTs -SERIAL_ORDER USART1 EMPTY EMPTY USART2 - -# USART1 for debug -PA9 USART1_TX USART1 -PA10 USART1_RX USART1 -define DEFAULT_SERIAL0_BAUD 57600 +define HAL_NO_GPIO_IRQ +define SERIAL_BUFFERS_SIZE 512 +define PORT_INT_REQUIRED_STACK 64 -# Enable the sensor voltage pin -PC13 VDD_3V3_SENSORS_EN OUTPUT HIGH +define DMA_RESERVE_SIZE 0 -# USART2 for GPS -PA2 USART2_TX USART2 SPEED_HIGH -PA3 USART2_RX USART2 SPEED_HIGH +# MAIN_STACK is stack for ISR handlers +MAIN_STACK 0x300 -# SWD debugging -PA13 JTMS-SWDIO SWD -PA14 JTCK-SWCLK SWD +# PROCESS_STACK controls stack for main thread +PROCESS_STACK 0xA00 -# SPI sensors -PA5 SPI1_SCK SPI1 -PA6 SPI1_MISO SPI1 -PA7 SPI1_MOSI SPI1 +define HAL_NO_MONITOR_THREAD -# SPI CS -PB12 MAG_CS CS -PA8 BARO_CS CS +# setup a small defaults.parm +define AP_PARAM_MAX_EMBEDDED_PARAM 512 -# Baro probe -SPIDEV dps310 SPI1 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ -BARO DPS310 SPI:dps310 +#ACT LED +PB3 LED OUTPUT HIGH +define HAL_LED_ON 1 -# Mag probe -SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ -COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180 -define AP_RM3100_REVERSAL_MASK 7 +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD -# PWM, WS2812 LED -PB8 TIM4_CH3 TIM4 PWM(1) GPIO(50) -PB9 TIM4_CH4 TIM4 PWM(2) GPIO(51) -PA15 TIM2_CH1 TIM2 PWM(3) GPIO(52) -PB4 TIM3_CH1 TIM3 PWM(4) GPIO(53) +#CAN bus +CAN_ORDER 1 +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 -define HAL_USE_ADC TRUE -define STM32_ADC_USE_ADC1 TRUE -#define HAL_DISABLE_ADC_DRIVER TRUE -PA0 VSENSE ADC1 SCALE(2) +define HAL_CAN_POOL_SIZE 6000 -define HAL_NO_GPIO_IRQ +# allow for reboot command for faster development +define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 -# avoid RCIN thread to save memory -define HAL_USE_RTC FALSE -define DMA_RESERVE_SIZE 0 +# keep ROMFS uncompressed as we don't have enough RAM +# to uncompress the bootloader at runtime +env ROMFS_UNCOMPRESSED True -# enable CAN support -PA11 CAN1_RX CAN1 -PA12 CAN1_TX CAN1 +# SERIAL +SERIAL_ORDER USART1 EMPTY USART3 -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 +# ESC +PB10 USART3_TX USART3 SPEED_HIGH +PB11 USART3_RX USART3 SPEED_HIGH -define HAL_NO_MONITOR_THREAD -define HAL_DEVICE_THREAD_STACK 768 - -# disable dual GPS and GPS blending to save flash space -define GPS_MAX_RECEIVERS 1 -define GPS_MAX_INSTANCES 1 -define HAL_COMPASS_MAX_SENSORS 1 - -# GPS+MAG+BARO+Buzzer+NeoPixels -define HAL_PERIPH_ENABLE_GPS -define HAL_PERIPH_GPS_PORT_DEFAULT 3 -define HAL_PERIPH_ENABLE_MAG -define HAL_PERIPH_ENABLE_BARO -define HAL_PERIPH_ENABLE_RC_OUT -define HAL_PERIPH_ENABLE_NOTIFY +# USART2 +#PA2 USART2_TX USART2 SPEED_HIGH +#PA3 USART2_RX USART2 SPEED_HIGH -# reserve 256 bytes for comms between app and bootloader -RAM_RESERVE_START 256 +# DEBUG +PB6 USART1_TX USART1 SPEED_HIGH +PB7 USART1_RX USART1 SPEED_HIGH -# allow for reboot command for faster development -define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 +# BATTERY +define HAL_PERIPH_ENABLE_BATTERY -# we setup a small defaults.parm -define AP_PARAM_MAX_EMBEDDED_PARAM 256 +define HAL_USE_ADC TRUE +define STM32_ADC_USE_ADC1 TRUE -#GPS M9N -PC11 M9EXTINT INPUT -PC10 M9RST INPUT -PC8 GPS_PPS_IN INPUT -PC7 M9SB INPUT +PB0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PB1 BATT_CURRENT_SENS ADC1 SCALE(1) + +define HAL_BATT_MONITOR_DEFAULT 0 +define HAL_BATT_VOLT_PIN 5 +define HAL_BATT_VOLT_SCALE 21.0 +define HAL_BATT_CURR_PIN 6 +define HAL_BATT_CURR_SCALE 40.0 + +#PWM +PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50) +PA9 TIM1_CH2 TIM1 PWM(2) GPIO(51) +PA10 TIM1_CH3 TIM1 PWM(3) GPIO(52) +PA11 TIM1_CH4 TIM1 PWM(4) GPIO(53) +PA15 TIM2_CH1 TIM2 PWM(5) GPIO(54) +PA2 TIM2_CH3 TIM2 PWM(6) GPIO(55) +PA3 TIM2_CH4 TIM2 PWM(7) GPIO(56) +PA1 TIM2_CH2 TIM2 PWM(8) GPIO(57) +PA6 TIM16_CH1 TIM16 PWM(9) GPIO(58) NODMA -define DEFAULT_NTF_LED_TYPES 455 +define HAL_PERIPH_ENABLE_RC_OUT +define HAL_PERIPH_ENABLE_NOTIFY -# bootloader embedding / bootloader flashing not available -define AP_BOOTLOADER_FLASHING_ENABLED 0 +# enable ESC control +define HAL_SUPPORT_RCOUT_SERIAL 1 +define HAL_WITH_ESC_TELEM 1 + +#GPIO LED +define HAL_HAVE_PIXRACER_LED +PB2 LED_RED OUTPUT OPENDRAIN HIGH GPIO(0) +PB4 LED_GREEN OUTPUT OPENDRAIN LOW GPIO(1) +PB5 LED_BLUE OUTPUT OPENDRAIN LOW GPIO(2) +define HAL_GPIO_A_LED_PIN 0 +define HAL_GPIO_B_LED_PIN 1 +define HAL_GPIO_C_LED_PIN 2 + +define HAL_SERIAL_ESC_COMM_ENABLED 1 +define HAL_RCIN_THREAD_ENABLED 1 From 43fda6b83c2162e44ea3919142d3ff85d3dd6b9e Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 17 Jun 2024 13:09:10 +0300 Subject: [PATCH 010/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index a08854f9cfb8d..6db7526ceafb5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -106,7 +106,7 @@ PA15 TIM2_CH1 TIM2 PWM(5) GPIO(54) PA2 TIM2_CH3 TIM2 PWM(6) GPIO(55) PA3 TIM2_CH4 TIM2 PWM(7) GPIO(56) PA1 TIM2_CH2 TIM2 PWM(8) GPIO(57) -PA6 TIM16_CH1 TIM16 PWM(9) GPIO(58) NODMA +#PA6 TIM16_CH1 TIM16 PWM(9) GPIO(58) NODMA define HAL_PERIPH_ENABLE_RC_OUT define HAL_PERIPH_ENABLE_NOTIFY From 1ab895aad3afcee75c6741b513c12aec5d9d9758 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 17 Jun 2024 13:16:01 +0300 Subject: [PATCH 011/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 6db7526ceafb5..290418f1325fc 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -15,7 +15,7 @@ env AP_PERIPH 1 STM32_ST_USE_TIMER 5 # board ID for firmware load -#APJ_BOARD_ID 1080 +APJ_BOARD_ID 1080 # crystal frequency OSCILLATOR_HZ 16000000 From efdd5f443e57b3006cf843fb7fd8731571359e64 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 17 Jun 2024 13:18:23 +0300 Subject: [PATCH 012/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 290418f1325fc..234ca2f491a0b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -126,3 +126,6 @@ define HAL_GPIO_C_LED_PIN 2 define HAL_SERIAL_ESC_COMM_ENABLED 1 define HAL_RCIN_THREAD_ENABLED 1 + +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 From a6c4b42e13a803140da3a374610f66d393323247 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 18 Jun 2024 12:14:16 +0300 Subject: [PATCH 013/143] Create hwdef-bl.dat --- .../hwdef/Inferno-PMU/hwdef-bl.dat | 131 ++++++++++++++++++ 1 file changed, 131 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat new file mode 100644 index 0000000000000..234ca2f491a0b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat @@ -0,0 +1,131 @@ +# MCU class and specific type +MCU STM32F4xx STM32F412Rx + +# bootloader starts firmware at 64k +FLASH_RESERVE_START_KB 64 + +# store parameters in pages 2 and 3 +define STORAGE_FLASH_PAGE 2 +define HAL_STORAGE_SIZE 8192 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +# ChibiOS system timer +STM32_ST_USE_TIMER 5 + +# board ID for firmware load +APJ_BOARD_ID 1080 + +# crystal frequency +OSCILLATOR_HZ 16000000 + +define CH_CFG_ST_FREQUENCY 1000000 + +# Flash available +FLASH_SIZE_KB 1024 + +STDOUT_SERIAL SD1 +STDOUT_BAUDRATE 57600 + +define HAL_NO_GPIO_IRQ +define SERIAL_BUFFERS_SIZE 512 +define PORT_INT_REQUIRED_STACK 64 + +define DMA_RESERVE_SIZE 0 + +# MAIN_STACK is stack for ISR handlers +MAIN_STACK 0x300 + +# PROCESS_STACK controls stack for main thread +PROCESS_STACK 0xA00 + +define HAL_NO_MONITOR_THREAD + +# setup a small defaults.parm +define AP_PARAM_MAX_EMBEDDED_PARAM 512 + +#ACT LED +PB3 LED OUTPUT HIGH +define HAL_LED_ON 1 + +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +#CAN bus +CAN_ORDER 1 +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 + +define HAL_CAN_POOL_SIZE 6000 + +# allow for reboot command for faster development +define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 + +# keep ROMFS uncompressed as we don't have enough RAM +# to uncompress the bootloader at runtime +env ROMFS_UNCOMPRESSED True + +# SERIAL +SERIAL_ORDER USART1 EMPTY USART3 + +# ESC +PB10 USART3_TX USART3 SPEED_HIGH +PB11 USART3_RX USART3 SPEED_HIGH + +# USART2 +#PA2 USART2_TX USART2 SPEED_HIGH +#PA3 USART2_RX USART2 SPEED_HIGH + +# DEBUG +PB6 USART1_TX USART1 SPEED_HIGH +PB7 USART1_RX USART1 SPEED_HIGH + +# BATTERY +define HAL_PERIPH_ENABLE_BATTERY + +define HAL_USE_ADC TRUE +define STM32_ADC_USE_ADC1 TRUE + +PB0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PB1 BATT_CURRENT_SENS ADC1 SCALE(1) + +define HAL_BATT_MONITOR_DEFAULT 0 +define HAL_BATT_VOLT_PIN 5 +define HAL_BATT_VOLT_SCALE 21.0 +define HAL_BATT_CURR_PIN 6 +define HAL_BATT_CURR_SCALE 40.0 + +#PWM +PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50) +PA9 TIM1_CH2 TIM1 PWM(2) GPIO(51) +PA10 TIM1_CH3 TIM1 PWM(3) GPIO(52) +PA11 TIM1_CH4 TIM1 PWM(4) GPIO(53) +PA15 TIM2_CH1 TIM2 PWM(5) GPIO(54) +PA2 TIM2_CH3 TIM2 PWM(6) GPIO(55) +PA3 TIM2_CH4 TIM2 PWM(7) GPIO(56) +PA1 TIM2_CH2 TIM2 PWM(8) GPIO(57) +#PA6 TIM16_CH1 TIM16 PWM(9) GPIO(58) NODMA + +define HAL_PERIPH_ENABLE_RC_OUT +define HAL_PERIPH_ENABLE_NOTIFY + +# enable ESC control +define HAL_SUPPORT_RCOUT_SERIAL 1 +define HAL_WITH_ESC_TELEM 1 + +#GPIO LED +define HAL_HAVE_PIXRACER_LED +PB2 LED_RED OUTPUT OPENDRAIN HIGH GPIO(0) +PB4 LED_GREEN OUTPUT OPENDRAIN LOW GPIO(1) +PB5 LED_BLUE OUTPUT OPENDRAIN LOW GPIO(2) +define HAL_GPIO_A_LED_PIN 0 +define HAL_GPIO_B_LED_PIN 1 +define HAL_GPIO_C_LED_PIN 2 + +define HAL_SERIAL_ESC_COMM_ENABLED 1 +define HAL_RCIN_THREAD_ENABLED 1 + +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 From 003bda9d249ca44f2733326f25bef9aa738eaebe Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 18 Jun 2024 12:15:08 +0300 Subject: [PATCH 014/143] Update hwdef-bl.dat --- .../hwdef/Inferno-PMU/hwdef-bl.dat | 146 ++++++------------ 1 file changed, 45 insertions(+), 101 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat index 234ca2f491a0b..8916aba52eca3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat @@ -1,22 +1,20 @@ +# hw definition file for processing by chibios_pins.py + +# Inferno-PMU Bootloader + # MCU class and specific type MCU STM32F4xx STM32F412Rx -# bootloader starts firmware at 64k -FLASH_RESERVE_START_KB 64 +FLASH_RESERVE_START_KB 0 +# two sectors for bootloader, two for storage +FLASH_BOOTLOADER_LOAD_KB 64 -# store parameters in pages 2 and 3 -define STORAGE_FLASH_PAGE 2 -define HAL_STORAGE_SIZE 8192 +# board ID for firmware load +APJ_BOARD_ID 1055 # setup build for a peripheral firmware env AP_PERIPH 1 -# ChibiOS system timer -STM32_ST_USE_TIMER 5 - -# board ID for firmware load -APJ_BOARD_ID 1080 - # crystal frequency OSCILLATOR_HZ 16000000 @@ -25,107 +23,53 @@ define CH_CFG_ST_FREQUENCY 1000000 # Flash available FLASH_SIZE_KB 1024 -STDOUT_SERIAL SD1 -STDOUT_BAUDRATE 57600 - -define HAL_NO_GPIO_IRQ -define SERIAL_BUFFERS_SIZE 512 -define PORT_INT_REQUIRED_STACK 64 +define HAL_STORAGE_SIZE 16384 -define DMA_RESERVE_SIZE 0 +# Enable the sensor voltage pin +PC13 VDD_3V3_SENSORS_EN OUTPUT HIGH -# MAIN_STACK is stack for ISR handlers -MAIN_STACK 0x300 +# order of UARTs +SERIAL_ORDER -# PROCESS_STACK controls stack for main thread -PROCESS_STACK 0xA00 +# USART1 +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 -define HAL_NO_MONITOR_THREAD - -# setup a small defaults.parm -define AP_PARAM_MAX_EMBEDDED_PARAM 512 - -#ACT LED -PB3 LED OUTPUT HIGH -define HAL_LED_ON 1 +# USART2 +PA2 USART2_TX USART2 +PA3 USART2_RX USART2 -# debugger support +# SWD debugging PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -#CAN bus -CAN_ORDER 1 -PB8 CAN1_RX CAN1 -PB9 CAN1_TX CAN1 +# enable CAN support +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 -define HAL_CAN_POOL_SIZE 6000 +# use DNA +define HAL_CAN_DEFAULT_NODE_ID 0 -# allow for reboot command for faster development -define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 +# reserve 256 bytes for comms between app and bootloader +RAM_RESERVE_START 256 -# keep ROMFS uncompressed as we don't have enough RAM -# to uncompress the bootloader at runtime -env ROMFS_UNCOMPRESSED True +# Add CS pins to ensure they are high in bootloader +PB12 MAG_CS CS +PA8 BARO_CS CS -# SERIAL -SERIAL_ORDER USART1 EMPTY USART3 +STDOUT_SERIAL SD1 +STDOUT_BAUDRATE 57600 -# ESC -PB10 USART3_TX USART3 SPEED_HIGH -PB11 USART3_RX USART3 SPEED_HIGH +define HAL_USE_SERIAL TRUE +define STM32_SERIAL_USE_USART1 TRUE +define STM32_SERIAL_USE_USART2 TRUE +define STM32_SERIAL_USE_USART3 FALSE -# USART2 -#PA2 USART2_TX USART2 SPEED_HIGH -#PA3 USART2_RX USART2 SPEED_HIGH - -# DEBUG -PB6 USART1_TX USART1 SPEED_HIGH -PB7 USART1_RX USART1 SPEED_HIGH - -# BATTERY -define HAL_PERIPH_ENABLE_BATTERY - -define HAL_USE_ADC TRUE -define STM32_ADC_USE_ADC1 TRUE - -PB0 BATT_VOLTAGE_SENS ADC1 SCALE(1) -PB1 BATT_CURRENT_SENS ADC1 SCALE(1) - -define HAL_BATT_MONITOR_DEFAULT 0 -define HAL_BATT_VOLT_PIN 5 -define HAL_BATT_VOLT_SCALE 21.0 -define HAL_BATT_CURR_PIN 6 -define HAL_BATT_CURR_SCALE 40.0 - -#PWM -PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50) -PA9 TIM1_CH2 TIM1 PWM(2) GPIO(51) -PA10 TIM1_CH3 TIM1 PWM(3) GPIO(52) -PA11 TIM1_CH4 TIM1 PWM(4) GPIO(53) -PA15 TIM2_CH1 TIM2 PWM(5) GPIO(54) -PA2 TIM2_CH3 TIM2 PWM(6) GPIO(55) -PA3 TIM2_CH4 TIM2 PWM(7) GPIO(56) -PA1 TIM2_CH2 TIM2 PWM(8) GPIO(57) -#PA6 TIM16_CH1 TIM16 PWM(9) GPIO(58) NODMA - -define HAL_PERIPH_ENABLE_RC_OUT -define HAL_PERIPH_ENABLE_NOTIFY - -# enable ESC control -define HAL_SUPPORT_RCOUT_SERIAL 1 -define HAL_WITH_ESC_TELEM 1 - -#GPIO LED -define HAL_HAVE_PIXRACER_LED -PB2 LED_RED OUTPUT OPENDRAIN HIGH GPIO(0) -PB4 LED_GREEN OUTPUT OPENDRAIN LOW GPIO(1) -PB5 LED_BLUE OUTPUT OPENDRAIN LOW GPIO(2) -define HAL_GPIO_A_LED_PIN 0 -define HAL_GPIO_B_LED_PIN 1 -define HAL_GPIO_C_LED_PIN 2 - -define HAL_SERIAL_ESC_COMM_ENABLED 1 -define HAL_RCIN_THREAD_ENABLED 1 - -# bootloader embedding / bootloader flashing not available -define AP_BOOTLOADER_FLASHING_ENABLED 0 +define HAL_NO_GPIO_IRQ +define HAL_USE_EMPTY_IO TRUE + +# make bl baudrate match debug baudrate for easier debugging +define BOOTLOADER_BAUDRATE 57600 + +# use a small bootloader timeout +define HAL_BOOTLOADER_TIMEOUT 1000 From d127219a8e36ddb817687508ab253025d9787c61 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 18 Jun 2024 12:15:41 +0300 Subject: [PATCH 015/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 234ca2f491a0b..ad183e0af918a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -15,7 +15,7 @@ env AP_PERIPH 1 STM32_ST_USE_TIMER 5 # board ID for firmware load -APJ_BOARD_ID 1080 +APJ_BOARD_ID 1055 # crystal frequency OSCILLATOR_HZ 16000000 From fb53f33c1e8ab5f4d92883c6b2127af274284f86 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 18 Jun 2024 13:31:34 +0300 Subject: [PATCH 016/143] Update hwdef-bl.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat index 8916aba52eca3..1a7c1d766db80 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat @@ -44,8 +44,8 @@ PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD # enable CAN support -PA11 CAN1_RX CAN1 -PA12 CAN1_TX CAN1 +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 # use DNA define HAL_CAN_DEFAULT_NODE_ID 0 From 6da6169a419801c6a7193591046a7c1cb13c574d Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 18 Jun 2024 13:45:01 +0300 Subject: [PATCH 017/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index ad183e0af918a..3c3da670cb1e2 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -2,7 +2,7 @@ MCU STM32F4xx STM32F412Rx # bootloader starts firmware at 64k -FLASH_RESERVE_START_KB 64 +FLASH_RESERVE_START_KB 0 # store parameters in pages 2 and 3 define STORAGE_FLASH_PAGE 2 From 5a8439896abe63b6964548866afd5f2203b8d6de Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 18 Jun 2024 13:54:21 +0300 Subject: [PATCH 018/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 3c3da670cb1e2..ad183e0af918a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -2,7 +2,7 @@ MCU STM32F4xx STM32F412Rx # bootloader starts firmware at 64k -FLASH_RESERVE_START_KB 0 +FLASH_RESERVE_START_KB 64 # store parameters in pages 2 and 3 define STORAGE_FLASH_PAGE 2 From 8f5e8bc43cd6f1a4d081405acf9b884060c00e72 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 18 Jun 2024 14:56:43 +0300 Subject: [PATCH 019/143] Update hwdef-bl.dat --- .../hwdef/Inferno-PMU/hwdef-bl.dat | 53 ++++++++++--------- 1 file changed, 28 insertions(+), 25 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat index 1a7c1d766db80..7ded3152ab2f0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat @@ -10,7 +10,7 @@ FLASH_RESERVE_START_KB 0 FLASH_BOOTLOADER_LOAD_KB 64 # board ID for firmware load -APJ_BOARD_ID 1055 +APJ_BOARD_ID 1001 # setup build for a peripheral firmware env AP_PERIPH 1 @@ -21,19 +21,24 @@ OSCILLATOR_HZ 16000000 define CH_CFG_ST_FREQUENCY 1000000 # Flash available -FLASH_SIZE_KB 1024 +FLASH_SIZE_KB 512 -define HAL_STORAGE_SIZE 16384 - -# Enable the sensor voltage pin -PC13 VDD_3V3_SENSORS_EN OUTPUT HIGH +STDOUT_SERIAL SD1 +STDOUT_BAUDRATE 57600 # order of UARTs SERIAL_ORDER +# use safety button to stay in bootloader +PB3 STAY_IN_BOOTLOADER INPUT PULLDOWN +define HAL_STAY_IN_BOOTLOADER_VALUE 1 + +PB12 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 1 + # USART1 -PA9 USART1_TX USART1 -PA10 USART1_RX USART1 +PB6 USART1_TX USART1 +PB7 USART1_RX USART1 # USART2 PA2 USART2_TX USART2 @@ -43,24 +48,8 @@ PA3 USART2_RX USART2 PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -# enable CAN support -PB8 CAN1_RX CAN1 -PB9 CAN1_TX CAN1 - -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 - -# reserve 256 bytes for comms between app and bootloader -RAM_RESERVE_START 256 - -# Add CS pins to ensure they are high in bootloader -PB12 MAG_CS CS -PA8 BARO_CS CS - -STDOUT_SERIAL SD1 -STDOUT_BAUDRATE 57600 - define HAL_USE_SERIAL TRUE + define STM32_SERIAL_USE_USART1 TRUE define STM32_SERIAL_USE_USART2 TRUE define STM32_SERIAL_USE_USART3 FALSE @@ -68,8 +57,22 @@ define STM32_SERIAL_USE_USART3 FALSE define HAL_NO_GPIO_IRQ define HAL_USE_EMPTY_IO TRUE +# avoid timer thread to save memory +define HAL_NO_TIMER_THREAD + +define DMA_RESERVE_SIZE 0 + +# enable CAN support +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 +PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + # make bl baudrate match debug baudrate for easier debugging define BOOTLOADER_BAUDRATE 57600 # use a small bootloader timeout define HAL_BOOTLOADER_TIMEOUT 1000 + +# Add CS pins to ensure they are high in bootloader +PA4 MAG_CS CS +PA10 MS5611_CS CS From c25e8906e31ca4b62939f4076ad25c45aab65902 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 18 Jun 2024 15:09:36 +0300 Subject: [PATCH 020/143] Update hwdef.dat --- .../hwdef/Inferno-PMU/hwdef.dat | 97 ++++++------------- 1 file changed, 29 insertions(+), 68 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index ad183e0af918a..91087892f3db6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -1,3 +1,6 @@ +# hw definition file for processing by chibios_pins.py +# MCU class and specific type + # MCU class and specific type MCU STM32F4xx STM32F412Rx @@ -5,25 +8,26 @@ MCU STM32F4xx STM32F412Rx FLASH_RESERVE_START_KB 64 # store parameters in pages 2 and 3 -define STORAGE_FLASH_PAGE 2 +STORAGE_FLASH_PAGE 2 define HAL_STORAGE_SIZE 8192 +# board ID for firmware load +APJ_BOARD_ID 1001 + # setup build for a peripheral firmware env AP_PERIPH 1 -# ChibiOS system timer STM32_ST_USE_TIMER 5 -# board ID for firmware load -APJ_BOARD_ID 1055 +# enable watchdog # crystal frequency OSCILLATOR_HZ 16000000 define CH_CFG_ST_FREQUENCY 1000000 -# Flash available -FLASH_SIZE_KB 1024 +# assume 512k flash part +FLASH_SIZE_KB 512 STDOUT_SERIAL SD1 STDOUT_BAUDRATE 57600 @@ -45,43 +49,13 @@ define HAL_NO_MONITOR_THREAD # setup a small defaults.parm define AP_PARAM_MAX_EMBEDDED_PARAM 512 -#ACT LED -PB3 LED OUTPUT HIGH -define HAL_LED_ON 1 +# order of UARTs +SERIAL_ORDER USART1 EMPTY EMPTY USART2 -# debugger support +# SWD debugging PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -#CAN bus -CAN_ORDER 1 -PB8 CAN1_RX CAN1 -PB9 CAN1_TX CAN1 - -define HAL_CAN_POOL_SIZE 6000 - -# allow for reboot command for faster development -define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 - -# keep ROMFS uncompressed as we don't have enough RAM -# to uncompress the bootloader at runtime -env ROMFS_UNCOMPRESSED True - -# SERIAL -SERIAL_ORDER USART1 EMPTY USART3 - -# ESC -PB10 USART3_TX USART3 SPEED_HIGH -PB11 USART3_RX USART3 SPEED_HIGH - -# USART2 -#PA2 USART2_TX USART2 SPEED_HIGH -#PA3 USART2_RX USART2 SPEED_HIGH - -# DEBUG -PB6 USART1_TX USART1 SPEED_HIGH -PB7 USART1_RX USART1 SPEED_HIGH - # BATTERY define HAL_PERIPH_ENABLE_BATTERY @@ -97,35 +71,22 @@ define HAL_BATT_VOLT_SCALE 21.0 define HAL_BATT_CURR_PIN 6 define HAL_BATT_CURR_SCALE 40.0 -#PWM -PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50) -PA9 TIM1_CH2 TIM1 PWM(2) GPIO(51) -PA10 TIM1_CH3 TIM1 PWM(3) GPIO(52) -PA11 TIM1_CH4 TIM1 PWM(4) GPIO(53) -PA15 TIM2_CH1 TIM2 PWM(5) GPIO(54) -PA2 TIM2_CH3 TIM2 PWM(6) GPIO(55) -PA3 TIM2_CH4 TIM2 PWM(7) GPIO(56) -PA1 TIM2_CH2 TIM2 PWM(8) GPIO(57) -#PA6 TIM16_CH1 TIM16 PWM(9) GPIO(58) NODMA - -define HAL_PERIPH_ENABLE_RC_OUT -define HAL_PERIPH_ENABLE_NOTIFY - -# enable ESC control -define HAL_SUPPORT_RCOUT_SERIAL 1 -define HAL_WITH_ESC_TELEM 1 - -#GPIO LED -define HAL_HAVE_PIXRACER_LED -PB2 LED_RED OUTPUT OPENDRAIN HIGH GPIO(0) -PB4 LED_GREEN OUTPUT OPENDRAIN LOW GPIO(1) -PB5 LED_BLUE OUTPUT OPENDRAIN LOW GPIO(2) -define HAL_GPIO_A_LED_PIN 0 -define HAL_GPIO_B_LED_PIN 1 -define HAL_GPIO_C_LED_PIN 2 - -define HAL_SERIAL_ESC_COMM_ENABLED 1 -define HAL_RCIN_THREAD_ENABLED 1 +# safety LED, active low +PB1 SAFE_LED OUTPUT HIGH +define SAFE_LED_ON 0 + +define HAL_NO_GPIO_IRQ + +define HAL_USE_RTC FALSE + +define DMA_RESERVE_SIZE 0 + +# enable CAN support +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 +PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +define HAL_CAN_POOL_SIZE 6000 # bootloader embedding / bootloader flashing not available define AP_BOOTLOADER_FLASHING_ENABLED 0 From 8623504d70d4dbbce3ec98f9c383e4f2a2e073cf Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 18 Jun 2024 15:12:29 +0300 Subject: [PATCH 021/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 4 ---- 1 file changed, 4 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 91087892f3db6..7440bda9e0abf 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -71,10 +71,6 @@ define HAL_BATT_VOLT_SCALE 21.0 define HAL_BATT_CURR_PIN 6 define HAL_BATT_CURR_SCALE 40.0 -# safety LED, active low -PB1 SAFE_LED OUTPUT HIGH -define SAFE_LED_ON 0 - define HAL_NO_GPIO_IRQ define HAL_USE_RTC FALSE From cdbd38d3ef53080a55dd58062e330ae4a2253224 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 18 Jun 2024 15:14:11 +0300 Subject: [PATCH 022/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 7440bda9e0abf..47b6e74c922f6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -50,7 +50,7 @@ define HAL_NO_MONITOR_THREAD define AP_PARAM_MAX_EMBEDDED_PARAM 512 # order of UARTs -SERIAL_ORDER USART1 EMPTY EMPTY USART2 +SERIAL_ORDER EMPTY EMPTY EMPTY EMPTY # SWD debugging PA13 JTMS-SWDIO SWD From 9b8c8ec5dd0dff5c05dd9448aa8bfa53dc4baf4a Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 18 Jun 2024 15:17:53 +0300 Subject: [PATCH 023/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 47b6e74c922f6..697ef91ff5908 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -50,7 +50,7 @@ define HAL_NO_MONITOR_THREAD define AP_PARAM_MAX_EMBEDDED_PARAM 512 # order of UARTs -SERIAL_ORDER EMPTY EMPTY EMPTY EMPTY +#SERIAL_ORDER EMPTY EMPTY EMPTY EMPTY # SWD debugging PA13 JTMS-SWDIO SWD From f2f911a1857c6f7094f2ed9eea558b5d58e8215b Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 18 Jun 2024 15:19:14 +0300 Subject: [PATCH 024/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 697ef91ff5908..afcc63483e704 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -50,7 +50,16 @@ define HAL_NO_MONITOR_THREAD define AP_PARAM_MAX_EMBEDDED_PARAM 512 # order of UARTs -#SERIAL_ORDER EMPTY EMPTY EMPTY EMPTY +SERIAL_ORDER USART1 EMPTY EMPTY USART2 + +# USART1 for debug +PB6 USART1_TX USART1 NODMA +PB7 USART1_RX USART1 NODMA +define DEFAULT_SERIAL0_BAUD 57600 + +# USART2 for GPS +PA2 USART2_TX USART2 NODMA +PA3 USART2_RX USART2 NODMA # SWD debugging PA13 JTMS-SWDIO SWD From fe4eee374003e4e70d862ae085ca0db2e9de2c37 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 18 Jun 2024 15:43:44 +0300 Subject: [PATCH 025/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index afcc63483e704..a744012d68f24 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -74,7 +74,7 @@ define STM32_ADC_USE_ADC1 TRUE PB0 BATT_VOLTAGE_SENS ADC1 SCALE(1) PB1 BATT_CURRENT_SENS ADC1 SCALE(1) -define HAL_BATT_MONITOR_DEFAULT 0 +define HAL_BATT_MONITOR_DEFAULT 1 define HAL_BATT_VOLT_PIN 5 define HAL_BATT_VOLT_SCALE 21.0 define HAL_BATT_CURR_PIN 6 From ea81d1b83def170c7d8690ef49254343d660c02f Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 18 Jun 2024 16:01:00 +0300 Subject: [PATCH 026/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index a744012d68f24..d81eec5af9b92 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -74,6 +74,7 @@ define STM32_ADC_USE_ADC1 TRUE PB0 BATT_VOLTAGE_SENS ADC1 SCALE(1) PB1 BATT_CURRENT_SENS ADC1 SCALE(1) +define HAL_PERIPH_ENABLE_BATTERY define HAL_BATT_MONITOR_DEFAULT 1 define HAL_BATT_VOLT_PIN 5 define HAL_BATT_VOLT_SCALE 21.0 From 0e9a5d87f01282e0e557efed7df33279b4de88f1 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 18 Jun 2024 16:18:58 +0300 Subject: [PATCH 027/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index d81eec5af9b92..670ecb7255790 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -67,15 +67,14 @@ PA14 JTCK-SWCLK SWD # BATTERY define HAL_PERIPH_ENABLE_BATTERY - +define AP_PERIPH_BATTERY_MODEL_NAME "Inferno-BattMon" define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE PB0 BATT_VOLTAGE_SENS ADC1 SCALE(1) PB1 BATT_CURRENT_SENS ADC1 SCALE(1) -define HAL_PERIPH_ENABLE_BATTERY -define HAL_BATT_MONITOR_DEFAULT 1 +define HAL_BATT_MONITOR_DEFAULT 26 define HAL_BATT_VOLT_PIN 5 define HAL_BATT_VOLT_SCALE 21.0 define HAL_BATT_CURR_PIN 6 From 72aeb66e222904eaf6b5191fa41dd0e5085a09d2 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 10:36:50 +0300 Subject: [PATCH 028/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 670ecb7255790..ef7853db44734 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -67,6 +67,7 @@ PA14 JTCK-SWCLK SWD # BATTERY define HAL_PERIPH_ENABLE_BATTERY +define AP_BATTERY_INA239_ENABLED 1 define AP_PERIPH_BATTERY_MODEL_NAME "Inferno-BattMon" define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE From 5c32a67419de46d834f03999e4fa541edab87e46 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 10:39:00 +0300 Subject: [PATCH 029/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index ef7853db44734..6f9c5e402b6a6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -67,7 +67,7 @@ PA14 JTCK-SWCLK SWD # BATTERY define HAL_PERIPH_ENABLE_BATTERY -define AP_BATTERY_INA239_ENABLED 1 +define AP_BATTERY_ANALOG_ENABLED 1 define AP_PERIPH_BATTERY_MODEL_NAME "Inferno-BattMon" define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE From 7cd000e8a7dd98ab20bb092788d97e623c9c0471 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 11:00:27 +0300 Subject: [PATCH 030/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 6f9c5e402b6a6..d0f9d9308d03b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -75,7 +75,7 @@ define STM32_ADC_USE_ADC1 TRUE PB0 BATT_VOLTAGE_SENS ADC1 SCALE(1) PB1 BATT_CURRENT_SENS ADC1 SCALE(1) -define HAL_BATT_MONITOR_DEFAULT 26 +define HAL_BATT_MONITOR_DEFAULT 8 define HAL_BATT_VOLT_PIN 5 define HAL_BATT_VOLT_SCALE 21.0 define HAL_BATT_CURR_PIN 6 From ed7f77f1acdedd475de9be69c7c69d99e830e829 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 11:07:17 +0300 Subject: [PATCH 031/143] Update hwdef.dat From 683df22f5dc5b749eb5a6d44225293c08ee65383 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 11:19:41 +0300 Subject: [PATCH 032/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index d0f9d9308d03b..6cc3829ce03f7 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -68,6 +68,7 @@ PA14 JTCK-SWCLK SWD # BATTERY define HAL_PERIPH_ENABLE_BATTERY define AP_BATTERY_ANALOG_ENABLED 1 +define HAL_ENABLE_DRONECAN_DRIVERS 1 define AP_PERIPH_BATTERY_MODEL_NAME "Inferno-BattMon" define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE From 432dec3481c061f0be430d99fe33cd1ef0abc66b Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 11:22:58 +0300 Subject: [PATCH 033/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 6cc3829ce03f7..3d6335d49c453 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -67,7 +67,7 @@ PA14 JTCK-SWCLK SWD # BATTERY define HAL_PERIPH_ENABLE_BATTERY -define AP_BATTERY_ANALOG_ENABLED 1 + define HAL_ENABLE_DRONECAN_DRIVERS 1 define AP_PERIPH_BATTERY_MODEL_NAME "Inferno-BattMon" define HAL_USE_ADC TRUE From 8ede96f8423d025618e28154beb6691fc145edb6 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 11:28:55 +0300 Subject: [PATCH 034/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 3d6335d49c453..32e49c44cdaef 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -68,7 +68,7 @@ PA14 JTCK-SWCLK SWD # BATTERY define HAL_PERIPH_ENABLE_BATTERY -define HAL_ENABLE_DRONECAN_DRIVERS 1 +define AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED 1 define AP_PERIPH_BATTERY_MODEL_NAME "Inferno-BattMon" define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE From aa0722446b6f4465351450f28f813eee0105d24c Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 11:30:26 +0300 Subject: [PATCH 035/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 32e49c44cdaef..e0d9c18c70b37 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -69,6 +69,7 @@ PA14 JTCK-SWCLK SWD define HAL_PERIPH_ENABLE_BATTERY define AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED 1 +define AP_BATTMONITOR_UAVCAN_MPPT_DEBUG 0 define AP_PERIPH_BATTERY_MODEL_NAME "Inferno-BattMon" define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE From 84035a81ec9dc2a5db8ab2271f2378caa27cef7a Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 11:55:16 +0300 Subject: [PATCH 036/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index e0d9c18c70b37..6921211ab4361 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -68,7 +68,7 @@ PA14 JTCK-SWCLK SWD # BATTERY define HAL_PERIPH_ENABLE_BATTERY -define AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED 1 +define HAL_ENABLE_DRONECAN_DRIVERS 1 define AP_BATTMONITOR_UAVCAN_MPPT_DEBUG 0 define AP_PERIPH_BATTERY_MODEL_NAME "Inferno-BattMon" define HAL_USE_ADC TRUE From e40759b813c4420c1f24ee5b6c274056d8b15ef5 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 11:56:52 +0300 Subject: [PATCH 037/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 6921211ab4361..eeecd0abf4bbd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -68,7 +68,7 @@ PA14 JTCK-SWCLK SWD # BATTERY define HAL_PERIPH_ENABLE_BATTERY -define HAL_ENABLE_DRONECAN_DRIVERS 1 +define HAL_ENABLE_DRONECAN_DRIVERS define AP_BATTMONITOR_UAVCAN_MPPT_DEBUG 0 define AP_PERIPH_BATTERY_MODEL_NAME "Inferno-BattMon" define HAL_USE_ADC TRUE From 4147d668acbddb5e631bf7158b5a259901d59102 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 11:59:41 +0300 Subject: [PATCH 038/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index eeecd0abf4bbd..7d74b0564a96c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -68,7 +68,7 @@ PA14 JTCK-SWCLK SWD # BATTERY define HAL_PERIPH_ENABLE_BATTERY -define HAL_ENABLE_DRONECAN_DRIVERS +define UAVCAN_BATTERY_INFO 1 define AP_BATTMONITOR_UAVCAN_MPPT_DEBUG 0 define AP_PERIPH_BATTERY_MODEL_NAME "Inferno-BattMon" define HAL_USE_ADC TRUE From 0554879b9692f3446ffe83777c54f7b08ed1a744 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 12:06:58 +0300 Subject: [PATCH 039/143] Update hwdef.dat --- .../hwdef/Inferno-PMU/hwdef.dat | 27 ++++++++++--------- 1 file changed, 15 insertions(+), 12 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 7d74b0564a96c..fadcc877ad488 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -66,22 +66,25 @@ PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD # BATTERY +# enable battery monitor define HAL_PERIPH_ENABLE_BATTERY +define AP_BATTERY_INA239_ENABLED 1 +define AP_BATTERY_INA239_SPI_DEVICE "INA23X" +define HAL_BATT_MONITOR_DEFAULT 26 +define AP_PERIPH_BATTERY_MODEL_NAME "MatekL431-BattMon" -define UAVCAN_BATTERY_INFO 1 -define AP_BATTMONITOR_UAVCAN_MPPT_DEBUG 0 -define AP_PERIPH_BATTERY_MODEL_NAME "Inferno-BattMon" -define HAL_USE_ADC TRUE -define STM32_ADC_USE_ADC1 TRUE +SPIDEV INA23X SPI1 DEVID1 SPARE_CS MODE1 10*MHZ 10*MHZ -PB0 BATT_VOLTAGE_SENS ADC1 SCALE(1) -PB1 BATT_CURRENT_SENS ADC1 SCALE(1) +# no ADC pins +define HAL_USE_ADC FALSE -define HAL_BATT_MONITOR_DEFAULT 8 -define HAL_BATT_VOLT_PIN 5 -define HAL_BATT_VOLT_SCALE 21.0 -define HAL_BATT_CURR_PIN 6 -define HAL_BATT_CURR_SCALE 40.0 +# disable unnecessary threads +define HAL_NO_MONITOR_THREAD +define HAL_NO_RCOUT_THREAD +define HAL_NO_TIMER_THREAD + +undef HAL_RCIN_THREAD_ENABLED +define HAL_RCIN_THREAD_ENABLED 0 define HAL_NO_GPIO_IRQ From 1212b8ff9f9049f8ff771bad2ed7eced13bd4294 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 12:07:51 +0300 Subject: [PATCH 040/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 10 ++-------- 1 file changed, 2 insertions(+), 8 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index fadcc877ad488..a25817448bdba 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -68,16 +68,10 @@ PA14 JTCK-SWCLK SWD # BATTERY # enable battery monitor define HAL_PERIPH_ENABLE_BATTERY -define AP_BATTERY_INA239_ENABLED 1 -define AP_BATTERY_INA239_SPI_DEVICE "INA23X" -define HAL_BATT_MONITOR_DEFAULT 26 +define AP_BATTERY_ANALOG_ENABLED 1 +define HAL_BATT_MONITOR_DEFAULT 8 define AP_PERIPH_BATTERY_MODEL_NAME "MatekL431-BattMon" -SPIDEV INA23X SPI1 DEVID1 SPARE_CS MODE1 10*MHZ 10*MHZ - -# no ADC pins -define HAL_USE_ADC FALSE - # disable unnecessary threads define HAL_NO_MONITOR_THREAD define HAL_NO_RCOUT_THREAD From 81ecb1807ed51f97f3d937e5d683d1e1f166d777 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 12:09:21 +0300 Subject: [PATCH 041/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index a25817448bdba..93179c08ff5a2 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -68,6 +68,18 @@ PA14 JTCK-SWCLK SWD # BATTERY # enable battery monitor define HAL_PERIPH_ENABLE_BATTERY +define HAL_USE_ADC TRUE +define STM32_ADC_USE_ADC1 TRUE + +PB0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PB1 BATT_CURRENT_SENS ADC1 SCALE(1) + +define HAL_BATT_MONITOR_DEFAULT 0 +define HAL_BATT_VOLT_PIN 5 +define HAL_BATT_VOLT_SCALE 21.0 +define HAL_BATT_CURR_PIN 6 +define HAL_BATT_CURR_SCALE 40.0 + define AP_BATTERY_ANALOG_ENABLED 1 define HAL_BATT_MONITOR_DEFAULT 8 define AP_PERIPH_BATTERY_MODEL_NAME "MatekL431-BattMon" From 2d817c49b5d14a90f6cb47f50054bdc0d4b26954 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 12:10:12 +0300 Subject: [PATCH 042/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 93179c08ff5a2..c6a6de1cd7985 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -74,14 +74,13 @@ define STM32_ADC_USE_ADC1 TRUE PB0 BATT_VOLTAGE_SENS ADC1 SCALE(1) PB1 BATT_CURRENT_SENS ADC1 SCALE(1) -define HAL_BATT_MONITOR_DEFAULT 0 +define HAL_BATT_MONITOR_DEFAULT 8 define HAL_BATT_VOLT_PIN 5 define HAL_BATT_VOLT_SCALE 21.0 define HAL_BATT_CURR_PIN 6 define HAL_BATT_CURR_SCALE 40.0 define AP_BATTERY_ANALOG_ENABLED 1 -define HAL_BATT_MONITOR_DEFAULT 8 define AP_PERIPH_BATTERY_MODEL_NAME "MatekL431-BattMon" # disable unnecessary threads From f3b2d59260b0f23eca2a513abadeb0302413ca8d Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 12:15:09 +0300 Subject: [PATCH 043/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index c6a6de1cd7985..5eec629795601 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -80,7 +80,6 @@ define HAL_BATT_VOLT_SCALE 21.0 define HAL_BATT_CURR_PIN 6 define HAL_BATT_CURR_SCALE 40.0 -define AP_BATTERY_ANALOG_ENABLED 1 define AP_PERIPH_BATTERY_MODEL_NAME "MatekL431-BattMon" # disable unnecessary threads From 9a420e7b58701ac864acb45bc334f2b10e794b2b Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 12:15:40 +0300 Subject: [PATCH 044/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 5eec629795601..234097aab4fb3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -83,7 +83,6 @@ define HAL_BATT_CURR_SCALE 40.0 define AP_PERIPH_BATTERY_MODEL_NAME "MatekL431-BattMon" # disable unnecessary threads -define HAL_NO_MONITOR_THREAD define HAL_NO_RCOUT_THREAD define HAL_NO_TIMER_THREAD From 1cec4273defdee02d7d79674f59b7ba040e83834 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 13:53:26 +0300 Subject: [PATCH 045/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 234097aab4fb3..7c666262f9003 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -65,6 +65,11 @@ PA3 USART2_RX USART2 NODMA PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD +# enable CAN support +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 +PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + # BATTERY # enable battery monitor define HAL_PERIPH_ENABLE_BATTERY @@ -83,6 +88,7 @@ define HAL_BATT_CURR_SCALE 40.0 define AP_PERIPH_BATTERY_MODEL_NAME "MatekL431-BattMon" # disable unnecessary threads +define HAL_NO_MONITOR_THREAD define HAL_NO_RCOUT_THREAD define HAL_NO_TIMER_THREAD @@ -95,11 +101,6 @@ define HAL_USE_RTC FALSE define DMA_RESERVE_SIZE 0 -# enable CAN support -PB8 CAN1_RX CAN1 -PB9 CAN1_TX CAN1 -PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW - define HAL_CAN_POOL_SIZE 6000 # bootloader embedding / bootloader flashing not available From b92bb641183b33734f84fd516878ef1d29b1cc21 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 13:59:42 +0300 Subject: [PATCH 046/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 7c666262f9003..57e86cc8a24d6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -70,9 +70,12 @@ PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW +define HAL_CAN_POOL_SIZE 6000 + # BATTERY # enable battery monitor define HAL_PERIPH_ENABLE_BATTERY + define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE @@ -92,16 +95,11 @@ define HAL_NO_MONITOR_THREAD define HAL_NO_RCOUT_THREAD define HAL_NO_TIMER_THREAD -undef HAL_RCIN_THREAD_ENABLED -define HAL_RCIN_THREAD_ENABLED 0 - define HAL_NO_GPIO_IRQ define HAL_USE_RTC FALSE define DMA_RESERVE_SIZE 0 -define HAL_CAN_POOL_SIZE 6000 - # bootloader embedding / bootloader flashing not available define AP_BOOTLOADER_FLASHING_ENABLED 0 From 8ccca89a611fc1c3686e8064aad5e307ff21ad6f Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 14:14:13 +0300 Subject: [PATCH 047/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 57e86cc8a24d6..baf0606194f41 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -88,6 +88,8 @@ define HAL_BATT_VOLT_SCALE 21.0 define HAL_BATT_CURR_PIN 6 define HAL_BATT_CURR_SCALE 40.0 +define AP_TEMPERATURE_SENSOR_ENABLED 1 + define AP_PERIPH_BATTERY_MODEL_NAME "MatekL431-BattMon" # disable unnecessary threads From 4fdb9c25b2dee2e3627534bbb5c4b72bbbe05fd8 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 14:49:40 +0300 Subject: [PATCH 048/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 12 ------------ 1 file changed, 12 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index baf0606194f41..3a19b3efd7a7e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -68,7 +68,6 @@ PA14 JTCK-SWCLK SWD # enable CAN support PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 -PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW define HAL_CAN_POOL_SIZE 6000 @@ -92,16 +91,5 @@ define AP_TEMPERATURE_SENSOR_ENABLED 1 define AP_PERIPH_BATTERY_MODEL_NAME "MatekL431-BattMon" -# disable unnecessary threads -define HAL_NO_MONITOR_THREAD -define HAL_NO_RCOUT_THREAD -define HAL_NO_TIMER_THREAD - -define HAL_NO_GPIO_IRQ - -define HAL_USE_RTC FALSE - -define DMA_RESERVE_SIZE 0 - # bootloader embedding / bootloader flashing not available define AP_BOOTLOADER_FLASHING_ENABLED 0 From 2fc34a871716d859bbc2e05cb61a081d8575bf7f Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 14:56:44 +0300 Subject: [PATCH 049/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 3a19b3efd7a7e..6a184b8276bf5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -91,5 +91,13 @@ define AP_TEMPERATURE_SENSOR_ENABLED 1 define AP_PERIPH_BATTERY_MODEL_NAME "MatekL431-BattMon" +# disable unnecessary threads +define HAL_NO_MONITOR_THREAD +define HAL_NO_RCOUT_THREAD +define HAL_NO_TIMER_THREAD + +undef HAL_RCIN_THREAD_ENABLED +define HAL_RCIN_THREAD_ENABLED 0 + # bootloader embedding / bootloader flashing not available define AP_BOOTLOADER_FLASHING_ENABLED 0 From 8cbd68a654a32a94218755cce78f3cd23d82b742 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 15:04:10 +0300 Subject: [PATCH 050/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 7 ------- 1 file changed, 7 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 6a184b8276bf5..c2e779f3034fa 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -89,15 +89,8 @@ define HAL_BATT_CURR_SCALE 40.0 define AP_TEMPERATURE_SENSOR_ENABLED 1 -define AP_PERIPH_BATTERY_MODEL_NAME "MatekL431-BattMon" - # disable unnecessary threads define HAL_NO_MONITOR_THREAD -define HAL_NO_RCOUT_THREAD -define HAL_NO_TIMER_THREAD - -undef HAL_RCIN_THREAD_ENABLED -define HAL_RCIN_THREAD_ENABLED 0 # bootloader embedding / bootloader flashing not available define AP_BOOTLOADER_FLASHING_ENABLED 0 From b69f40d3d682cd0a23c6c5702a2343b24ce81a7c Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 15:09:44 +0300 Subject: [PATCH 051/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index c2e779f3034fa..862bc6538076c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -91,6 +91,11 @@ define AP_TEMPERATURE_SENSOR_ENABLED 1 # disable unnecessary threads define HAL_NO_MONITOR_THREAD +define HAL_NO_RCOUT_THREAD +define HAL_NO_TIMER_THREAD + +undef HAL_RCIN_THREAD_ENABLED +define HAL_RCIN_THREAD_ENABLED 0 # bootloader embedding / bootloader flashing not available define AP_BOOTLOADER_FLASHING_ENABLED 0 From d3430eecb1cf9a329c57fbe9c5e4fd790e69ddaa Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 15:11:27 +0300 Subject: [PATCH 052/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 7 ------- 1 file changed, 7 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 862bc6538076c..18f0c629fc608 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -44,11 +44,6 @@ MAIN_STACK 0x300 # PROCESS_STACK controls stack for main thread PROCESS_STACK 0xA00 -define HAL_NO_MONITOR_THREAD - -# setup a small defaults.parm -define AP_PARAM_MAX_EMBEDDED_PARAM 512 - # order of UARTs SERIAL_ORDER USART1 EMPTY EMPTY USART2 @@ -87,8 +82,6 @@ define HAL_BATT_VOLT_SCALE 21.0 define HAL_BATT_CURR_PIN 6 define HAL_BATT_CURR_SCALE 40.0 -define AP_TEMPERATURE_SENSOR_ENABLED 1 - # disable unnecessary threads define HAL_NO_MONITOR_THREAD define HAL_NO_RCOUT_THREAD From 3c678743e6d9959cbd75d265f6c64a2037f53466 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 15:19:28 +0300 Subject: [PATCH 053/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 18f0c629fc608..e8eadc7d16753 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -63,6 +63,7 @@ PA14 JTCK-SWCLK SWD # enable CAN support PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 +PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW define HAL_CAN_POOL_SIZE 6000 From 61fcf545351e5c0f6226435124d9ac215b37109e Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 19 Jun 2024 15:51:58 +0300 Subject: [PATCH 054/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 6 ------ 1 file changed, 6 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index e8eadc7d16753..67212834d7df0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -77,12 +77,6 @@ define STM32_ADC_USE_ADC1 TRUE PB0 BATT_VOLTAGE_SENS ADC1 SCALE(1) PB1 BATT_CURRENT_SENS ADC1 SCALE(1) -define HAL_BATT_MONITOR_DEFAULT 8 -define HAL_BATT_VOLT_PIN 5 -define HAL_BATT_VOLT_SCALE 21.0 -define HAL_BATT_CURR_PIN 6 -define HAL_BATT_CURR_SCALE 40.0 - # disable unnecessary threads define HAL_NO_MONITOR_THREAD define HAL_NO_RCOUT_THREAD From f9243121c134d74e5e08323ed04d8b0ec17763a7 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 10:48:43 +0300 Subject: [PATCH 055/143] Update hwdef.dat --- .../hwdef/Inferno-PMU/hwdef.dat | 52 +++++++++++-------- 1 file changed, 31 insertions(+), 21 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 67212834d7df0..27f068cd1fb16 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -44,38 +44,51 @@ MAIN_STACK 0x300 # PROCESS_STACK controls stack for main thread PROCESS_STACK 0xA00 -# order of UARTs -SERIAL_ORDER USART1 EMPTY EMPTY USART2 - -# USART1 for debug -PB6 USART1_TX USART1 NODMA -PB7 USART1_RX USART1 NODMA -define DEFAULT_SERIAL0_BAUD 57600 +define HAL_NO_MONITOR_THREAD -# USART2 for GPS -PA2 USART2_TX USART2 NODMA -PA3 USART2_RX USART2 NODMA +# we setup a small defaults.parm +define AP_PARAM_MAX_EMBEDDED_PARAM 512 -# SWD debugging +# debugger support PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -# enable CAN support +# --------------------- SPI1 RM3100 ----------------------- +PA5 SPI1_SCK SPI1 +PB4 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PA4 MAG_CS CS +PB2 SPARE_CS CS + +# ---------------------- CAN bus ------------------------- +CAN_ORDER 1 + PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 -PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW +# PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW define HAL_CAN_POOL_SIZE 6000 -# BATTERY +# allow for reboot command for faster development +define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 + +# keep ROMFS uncompressed as we don't have enough RAM +# to uncompress the bootloader at runtime +env ROMFS_UNCOMPRESSED True + +define HAL_RCIN_THREAD_ENABLED 1 + # enable battery monitor define HAL_PERIPH_ENABLE_BATTERY +define AP_BATTERY_INA239_ENABLED 1 +define AP_BATTERY_INA239_SPI_DEVICE "INA23X" +define HAL_BATT_MONITOR_DEFAULT 26 +define AP_PERIPH_BATTERY_MODEL_NAME "MatekL431-BattMon" -define HAL_USE_ADC TRUE -define STM32_ADC_USE_ADC1 TRUE +SPIDEV INA23X SPI1 DEVID1 SPARE_CS MODE1 10*MHZ 10*MHZ -PB0 BATT_VOLTAGE_SENS ADC1 SCALE(1) -PB1 BATT_CURRENT_SENS ADC1 SCALE(1) +# no ADC pins +define HAL_USE_ADC FALSE # disable unnecessary threads define HAL_NO_MONITOR_THREAD @@ -84,6 +97,3 @@ define HAL_NO_TIMER_THREAD undef HAL_RCIN_THREAD_ENABLED define HAL_RCIN_THREAD_ENABLED 0 - -# bootloader embedding / bootloader flashing not available -define AP_BOOTLOADER_FLASHING_ENABLED 0 From a901ad3a1977588c200561d60e6256cf654e571d Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 10:49:56 +0300 Subject: [PATCH 056/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 27f068cd1fb16..2103f68c45976 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -97,3 +97,6 @@ define HAL_NO_TIMER_THREAD undef HAL_RCIN_THREAD_ENABLED define HAL_RCIN_THREAD_ENABLED 0 + +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 From 384676e21cd679db57ad3258349a6297e79470ee Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 10:51:13 +0300 Subject: [PATCH 057/143] Update hwdef.dat --- .../AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 2103f68c45976..930124284bc1a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -69,6 +69,20 @@ PB9 CAN1_TX CAN1 define HAL_CAN_POOL_SIZE 6000 +SERIAL_ORDER USART1 USART2 USART3 + +# USART1 for debug +PB6 USART1_TX USART1 SPEED_HIGH +PB7 USART1_RX USART1 SPEED_HIGH + +# USART2 for MSP +PA2 USART2_TX USART2 SPEED_HIGH +PA3 USART2_RX USART2 SPEED_HIGH + +# USART3 for GPS +PB10 USART3_TX USART3 SPEED_HIGH NODMA +PB11 USART3_RX USART3 SPEED_HIGH NODMA + # allow for reboot command for faster development define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 From ee5d9f818a8b61c2485f8e279f274b9d65b25b5d Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 11:07:45 +0300 Subject: [PATCH 058/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 930124284bc1a..674c240b77a3b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -65,7 +65,7 @@ CAN_ORDER 1 PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 -# PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW +PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW define HAL_CAN_POOL_SIZE 6000 From 3641441b2c85f60e36bb87566e2c25356c8ce9a4 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 11:36:00 +0300 Subject: [PATCH 059/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 674c240b77a3b..2653664f92b0b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -8,8 +8,8 @@ MCU STM32F4xx STM32F412Rx FLASH_RESERVE_START_KB 64 # store parameters in pages 2 and 3 -STORAGE_FLASH_PAGE 2 -define HAL_STORAGE_SIZE 8192 +STORAGE_FLASH_PAGE 18 +define HAL_STORAGE_SIZE 800 # board ID for firmware load APJ_BOARD_ID 1001 @@ -96,7 +96,7 @@ define HAL_RCIN_THREAD_ENABLED 1 define HAL_PERIPH_ENABLE_BATTERY define AP_BATTERY_INA239_ENABLED 1 define AP_BATTERY_INA239_SPI_DEVICE "INA23X" -define HAL_BATT_MONITOR_DEFAULT 26 +define HAL_BATT_MONITOR_DEFAULT 8 define AP_PERIPH_BATTERY_MODEL_NAME "MatekL431-BattMon" SPIDEV INA23X SPI1 DEVID1 SPARE_CS MODE1 10*MHZ 10*MHZ From d4f3d8af3ef0c77661bf5d0fab85834584fd05d7 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 11:36:45 +0300 Subject: [PATCH 060/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 2653664f92b0b..ba7b413606a47 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -9,7 +9,7 @@ FLASH_RESERVE_START_KB 64 # store parameters in pages 2 and 3 STORAGE_FLASH_PAGE 18 -define HAL_STORAGE_SIZE 800 +define HAL_STORAGE_SIZE 8192 # board ID for firmware load APJ_BOARD_ID 1001 From 6d0d76400adc494c42d9692ccca89e6c5d5a31b3 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 11:37:23 +0300 Subject: [PATCH 061/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index ba7b413606a47..d5423c0a2f92d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -8,7 +8,7 @@ MCU STM32F4xx STM32F412Rx FLASH_RESERVE_START_KB 64 # store parameters in pages 2 and 3 -STORAGE_FLASH_PAGE 18 +STORAGE_FLASH_PAGE 2 define HAL_STORAGE_SIZE 8192 # board ID for firmware load From 4562789f0ac0a0e6852c2e9f890911829f03db22 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 11:52:21 +0300 Subject: [PATCH 062/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index d5423c0a2f92d..bc9bc3b8041ff 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -94,8 +94,7 @@ define HAL_RCIN_THREAD_ENABLED 1 # enable battery monitor define HAL_PERIPH_ENABLE_BATTERY -define AP_BATTERY_INA239_ENABLED 1 -define AP_BATTERY_INA239_SPI_DEVICE "INA23X" +define AP_BATTERY_ENABLED 1 define HAL_BATT_MONITOR_DEFAULT 8 define AP_PERIPH_BATTERY_MODEL_NAME "MatekL431-BattMon" From 9d93a68300a11434ef2ceb5cff3de708b4d690dc Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 11:57:08 +0300 Subject: [PATCH 063/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index bc9bc3b8041ff..ed69becac7530 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -94,7 +94,13 @@ define HAL_RCIN_THREAD_ENABLED 1 # enable battery monitor define HAL_PERIPH_ENABLE_BATTERY -define AP_BATTERY_ENABLED 1 + +define HAL_USE_ADC TRUE +define STM32_ADC_USE_ADC1 TRUE + +PB0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PB1 BATT_CURRENT_SENS ADC1 SCALE(1) + define HAL_BATT_MONITOR_DEFAULT 8 define AP_PERIPH_BATTERY_MODEL_NAME "MatekL431-BattMon" From c698756803b4363f07ecce6349badbbe87492d10 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 11:57:53 +0300 Subject: [PATCH 064/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 3 --- 1 file changed, 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index ed69becac7530..47237bf085450 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -106,9 +106,6 @@ define AP_PERIPH_BATTERY_MODEL_NAME "MatekL431-BattMon" SPIDEV INA23X SPI1 DEVID1 SPARE_CS MODE1 10*MHZ 10*MHZ -# no ADC pins -define HAL_USE_ADC FALSE - # disable unnecessary threads define HAL_NO_MONITOR_THREAD define HAL_NO_RCOUT_THREAD From 07984f112225579716ca2bda672383e22143ae8d Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 12:20:29 +0300 Subject: [PATCH 065/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 6 ------ 1 file changed, 6 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 47237bf085450..dba1ebfe75a96 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -38,12 +38,6 @@ define PORT_INT_REQUIRED_STACK 64 define DMA_RESERVE_SIZE 0 -# MAIN_STACK is stack for ISR handlers -MAIN_STACK 0x300 - -# PROCESS_STACK controls stack for main thread -PROCESS_STACK 0xA00 - define HAL_NO_MONITOR_THREAD # we setup a small defaults.parm From 9ad69082da3d50c7298818b39751fef817884991 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 12:57:26 +0300 Subject: [PATCH 066/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index dba1ebfe75a96..c31e773892c1f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -87,7 +87,7 @@ env ROMFS_UNCOMPRESSED True define HAL_RCIN_THREAD_ENABLED 1 # enable battery monitor -define HAL_PERIPH_ENABLE_BATTERY +define HAL_PERIPH_ENABLE_BATTERY_BALANCER define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE From 3b7064134ea04f5638e32d527fd25e9fa69a3bac Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 12:58:23 +0300 Subject: [PATCH 067/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index c31e773892c1f..d00748350b41f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -87,7 +87,7 @@ env ROMFS_UNCOMPRESSED True define HAL_RCIN_THREAD_ENABLED 1 # enable battery monitor -define HAL_PERIPH_ENABLE_BATTERY_BALANCER +define HAL_PERIPH_ENABLE_BATTERY_BALANCE define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE From dc84d560c68d0c7a4d6b5b9d7cb500160a21837d Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 14:03:38 +0300 Subject: [PATCH 068/143] Update hwdef.dat --- .../hwdef/Inferno-PMU/hwdef.dat | 54 +++---------------- 1 file changed, 8 insertions(+), 46 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index d00748350b41f..65d79dc89bb27 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -47,47 +47,16 @@ define AP_PARAM_MAX_EMBEDDED_PARAM 512 PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -# --------------------- SPI1 RM3100 ----------------------- -PA5 SPI1_SCK SPI1 -PB4 SPI1_MISO SPI1 -PA7 SPI1_MOSI SPI1 -PA4 MAG_CS CS -PB2 SPARE_CS CS - -# ---------------------- CAN bus ------------------------- +#CAN bus CAN_ORDER 1 - PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW define HAL_CAN_POOL_SIZE 6000 -SERIAL_ORDER USART1 USART2 USART3 - -# USART1 for debug -PB6 USART1_TX USART1 SPEED_HIGH -PB7 USART1_RX USART1 SPEED_HIGH - -# USART2 for MSP -PA2 USART2_TX USART2 SPEED_HIGH -PA3 USART2_RX USART2 SPEED_HIGH - -# USART3 for GPS -PB10 USART3_TX USART3 SPEED_HIGH NODMA -PB11 USART3_RX USART3 SPEED_HIGH NODMA - -# allow for reboot command for faster development -define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 - -# keep ROMFS uncompressed as we don't have enough RAM -# to uncompress the bootloader at runtime -env ROMFS_UNCOMPRESSED True - -define HAL_RCIN_THREAD_ENABLED 1 - -# enable battery monitor -define HAL_PERIPH_ENABLE_BATTERY_BALANCE +# BATTERY +define HAL_PERIPH_ENABLE_BATTERY define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE @@ -95,18 +64,11 @@ define STM32_ADC_USE_ADC1 TRUE PB0 BATT_VOLTAGE_SENS ADC1 SCALE(1) PB1 BATT_CURRENT_SENS ADC1 SCALE(1) -define HAL_BATT_MONITOR_DEFAULT 8 -define AP_PERIPH_BATTERY_MODEL_NAME "MatekL431-BattMon" - -SPIDEV INA23X SPI1 DEVID1 SPARE_CS MODE1 10*MHZ 10*MHZ - -# disable unnecessary threads -define HAL_NO_MONITOR_THREAD -define HAL_NO_RCOUT_THREAD -define HAL_NO_TIMER_THREAD - -undef HAL_RCIN_THREAD_ENABLED -define HAL_RCIN_THREAD_ENABLED 0 +define HAL_BATT_MONITOR_DEFAULT 0 +define HAL_BATT_VOLT_PIN 5 +define HAL_BATT_VOLT_SCALE 21.0 +define HAL_BATT_CURR_PIN 6 +define HAL_BATT_CURR_SCALE 40.0 # bootloader embedding / bootloader flashing not available define AP_BOOTLOADER_FLASHING_ENABLED 0 From 82755fcd9f8a57dedb91a7e3d211bd2f275af0e9 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 14:05:03 +0300 Subject: [PATCH 069/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 3 --- 1 file changed, 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 65d79dc89bb27..8f07370cb9693 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -29,9 +29,6 @@ define CH_CFG_ST_FREQUENCY 1000000 # assume 512k flash part FLASH_SIZE_KB 512 -STDOUT_SERIAL SD1 -STDOUT_BAUDRATE 57600 - define HAL_NO_GPIO_IRQ define SERIAL_BUFFERS_SIZE 512 define PORT_INT_REQUIRED_STACK 64 From dcab8dac1c3f7b862482e26844766e81b14b4223 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 14:07:24 +0300 Subject: [PATCH 070/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 8f07370cb9693..b2cc9546e8241 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -30,7 +30,7 @@ define CH_CFG_ST_FREQUENCY 1000000 FLASH_SIZE_KB 512 define HAL_NO_GPIO_IRQ -define SERIAL_BUFFERS_SIZE 512 +#define SERIAL_BUFFERS_SIZE 512 define PORT_INT_REQUIRED_STACK 64 define DMA_RESERVE_SIZE 0 From 879d5a6ff4f0e47f30f35a36e78ad62205c03a04 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 14:08:38 +0300 Subject: [PATCH 071/143] Update hwdef.dat --- .../AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 14 +++++++++++++- 1 file changed, 13 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index b2cc9546e8241..f0e0df6efc07c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -30,7 +30,7 @@ define CH_CFG_ST_FREQUENCY 1000000 FLASH_SIZE_KB 512 define HAL_NO_GPIO_IRQ -#define SERIAL_BUFFERS_SIZE 512 +define SERIAL_BUFFERS_SIZE 512 define PORT_INT_REQUIRED_STACK 64 define DMA_RESERVE_SIZE 0 @@ -40,6 +40,18 @@ define HAL_NO_MONITOR_THREAD # we setup a small defaults.parm define AP_PARAM_MAX_EMBEDDED_PARAM 512 +# order of UARTs +SERIAL_ORDER USART1 EMPTY EMPTY USART2 + +# USART1 for debug +PB6 USART1_TX USART1 NODMA +PB7 USART1_RX USART1 NODMA +define DEFAULT_SERIAL0_BAUD 57600 + +# USART2 for GPS +PA2 USART2_TX USART2 NODMA +PA3 USART2_RX USART2 NODMA + # debugger support PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD From 8cbb25fc977fcaf1760e3a20ecd592c1fdaa0a32 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 14:39:32 +0300 Subject: [PATCH 072/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 11 +++-------- 1 file changed, 3 insertions(+), 8 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index f0e0df6efc07c..f03ce0e25fade 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -70,14 +70,9 @@ define HAL_PERIPH_ENABLE_BATTERY define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE -PB0 BATT_VOLTAGE_SENS ADC1 SCALE(1) -PB1 BATT_CURRENT_SENS ADC1 SCALE(1) - -define HAL_BATT_MONITOR_DEFAULT 0 -define HAL_BATT_VOLT_PIN 5 -define HAL_BATT_VOLT_SCALE 21.0 -define HAL_BATT_CURR_PIN 6 -define HAL_BATT_CURR_SCALE 40.0 +PA2 BATT_CURRENT_SENS ADC1 SCALE(1) + +define HAL_BATT_MONITOR_DEFAULT 8 # bootloader embedding / bootloader flashing not available define AP_BOOTLOADER_FLASHING_ENABLED 0 From 0859c6c33ac179bdbbf93dc306c62ef1fda1fc67 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 14:40:19 +0300 Subject: [PATCH 073/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index f03ce0e25fade..8b9dbe4a09059 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -41,17 +41,13 @@ define HAL_NO_MONITOR_THREAD define AP_PARAM_MAX_EMBEDDED_PARAM 512 # order of UARTs -SERIAL_ORDER USART1 EMPTY EMPTY USART2 +SERIAL_ORDER USART1 EMPTY EMPTY EMPTY # USART1 for debug PB6 USART1_TX USART1 NODMA PB7 USART1_RX USART1 NODMA define DEFAULT_SERIAL0_BAUD 57600 -# USART2 for GPS -PA2 USART2_TX USART2 NODMA -PA3 USART2_RX USART2 NODMA - # debugger support PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD From 295b073f648fb6c8e5a1210f44c0abe3792a7346 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 14:49:17 +0300 Subject: [PATCH 074/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 8b9dbe4a09059..10c1d0e65c398 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -67,7 +67,7 @@ define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE PA2 BATT_CURRENT_SENS ADC1 SCALE(1) - +define HAL_BATT_VOLT_PIN 16 define HAL_BATT_MONITOR_DEFAULT 8 # bootloader embedding / bootloader flashing not available From 465a7cac2f42c39cf3a91aaa3eb743984887d814 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 14:52:13 +0300 Subject: [PATCH 075/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 10c1d0e65c398..895c0c84edde6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -67,7 +67,7 @@ define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE PA2 BATT_CURRENT_SENS ADC1 SCALE(1) -define HAL_BATT_VOLT_PIN 16 +define HAL_BATT_VOLT_PIN 2 define HAL_BATT_MONITOR_DEFAULT 8 # bootloader embedding / bootloader flashing not available From cfa40c347a034a39247c9d3725c57ae2373352ba Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 14:54:22 +0300 Subject: [PATCH 076/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 895c0c84edde6..71cb4aedfca0a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -67,8 +67,9 @@ define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE PA2 BATT_CURRENT_SENS ADC1 SCALE(1) -define HAL_BATT_VOLT_PIN 2 define HAL_BATT_MONITOR_DEFAULT 8 +define HAL_BATT_CURR_PIN 2 + # bootloader embedding / bootloader flashing not available define AP_BOOTLOADER_FLASHING_ENABLED 0 From a93f4464cc4a13b1add9a685580791acc9baf360 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 15:20:10 +0300 Subject: [PATCH 077/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 71cb4aedfca0a..8eda1f541c182 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -2,7 +2,7 @@ # MCU class and specific type # MCU class and specific type -MCU STM32F4xx STM32F412Rx +MCU STM32F412Rx # bootloader starts firmware at 64k FLASH_RESERVE_START_KB 64 From 2028de6bbdcc8525ba91746b4b8492122b2aec99 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 15:23:26 +0300 Subject: [PATCH 078/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 8eda1f541c182..c0719f60d150e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -2,7 +2,7 @@ # MCU class and specific type # MCU class and specific type -MCU STM32F412Rx +MCU STM32F4xx STM32F412Rx # bootloader starts firmware at 64k FLASH_RESERVE_START_KB 64 @@ -69,7 +69,7 @@ define STM32_ADC_USE_ADC1 TRUE PA2 BATT_CURRENT_SENS ADC1 SCALE(1) define HAL_BATT_MONITOR_DEFAULT 8 define HAL_BATT_CURR_PIN 2 - +define HAL_BATT_CURR_SCALE 40.0 # bootloader embedding / bootloader flashing not available define AP_BOOTLOADER_FLASHING_ENABLED 0 From 020eac4932eccf1b9dec5252d4969ee57ad804f9 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 15:37:54 +0300 Subject: [PATCH 079/143] Update hwdef-bl.dat --- .../AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat | 10 +--------- 1 file changed, 1 insertion(+), 9 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat index 7ded3152ab2f0..5e3b831cfb63c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat @@ -29,10 +29,6 @@ STDOUT_BAUDRATE 57600 # order of UARTs SERIAL_ORDER -# use safety button to stay in bootloader -PB3 STAY_IN_BOOTLOADER INPUT PULLDOWN -define HAL_STAY_IN_BOOTLOADER_VALUE 1 - PB12 LED_BOOTLOADER OUTPUT LOW define HAL_LED_ON 1 @@ -40,10 +36,6 @@ define HAL_LED_ON 1 PB6 USART1_TX USART1 PB7 USART1_RX USART1 -# USART2 -PA2 USART2_TX USART2 -PA3 USART2_RX USART2 - # SWD debugging PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD @@ -51,7 +43,7 @@ PA14 JTCK-SWCLK SWD define HAL_USE_SERIAL TRUE define STM32_SERIAL_USE_USART1 TRUE -define STM32_SERIAL_USE_USART2 TRUE +define STM32_SERIAL_USE_USART2 FALSE define STM32_SERIAL_USE_USART3 FALSE define HAL_NO_GPIO_IRQ From 85970d32069ae0daa888acfa3d38c6235d858bac Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 15:46:57 +0300 Subject: [PATCH 080/143] Update hwdef-bl.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat index 5e3b831cfb63c..17f1dd3efef1a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat @@ -55,9 +55,9 @@ define HAL_NO_TIMER_THREAD define DMA_RESERVE_SIZE 0 # enable CAN support -PB8 CAN1_RX CAN1 -PB9 CAN1_TX CAN1 -PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW +#PB8 CAN1_RX CAN1 +#PB9 CAN1_TX CAN1 +#PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW # make bl baudrate match debug baudrate for easier debugging define BOOTLOADER_BAUDRATE 57600 From 36ef68a72504ab90037bbc440ca1d4a4c4866d73 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 15:52:31 +0300 Subject: [PATCH 081/143] Update hwdef-bl.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat index 17f1dd3efef1a..8f0d0c1c2407e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat @@ -55,8 +55,8 @@ define HAL_NO_TIMER_THREAD define DMA_RESERVE_SIZE 0 # enable CAN support -#PB8 CAN1_RX CAN1 -#PB9 CAN1_TX CAN1 +# PB8 CAN1_RX CAN1 +# PB9 CAN1_TX CAN1 #PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW # make bl baudrate match debug baudrate for easier debugging From 8e40db6c4d1efba1e007e4dd55c75e45f8b794c9 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 20 Jun 2024 15:55:36 +0300 Subject: [PATCH 082/143] Update hwdef-bl.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat index 8f0d0c1c2407e..5bddb38ab9d78 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat @@ -55,9 +55,9 @@ define HAL_NO_TIMER_THREAD define DMA_RESERVE_SIZE 0 # enable CAN support -# PB8 CAN1_RX CAN1 -# PB9 CAN1_TX CAN1 -#PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 +# PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW # make bl baudrate match debug baudrate for easier debugging define BOOTLOADER_BAUDRATE 57600 From eed603db54ee23a30d1efedb39f486aa275bd6b2 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Fri, 21 Jun 2024 13:40:08 +0300 Subject: [PATCH 083/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index c0719f60d150e..47b53478538f4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -62,6 +62,7 @@ define HAL_CAN_POOL_SIZE 6000 # BATTERY define HAL_PERIPH_ENABLE_BATTERY +define AP_BATTERY_ANALOG_ENABLED 1 define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE From de3ec5b2ed67fb74d9493e0b632abec040d138c8 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Fri, 21 Jun 2024 13:47:36 +0300 Subject: [PATCH 084/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 47b53478538f4..d3e6109dc6afe 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -62,7 +62,7 @@ define HAL_CAN_POOL_SIZE 6000 # BATTERY define HAL_PERIPH_ENABLE_BATTERY -define AP_BATTERY_ANALOG_ENABLED 1 +# define AP_BATTERY_ANALOG_ENABLED 1 define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE From 1920098af8d4dd8d4166d8ce0f0bdd54a44ba9c1 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Fri, 21 Jun 2024 14:03:10 +0300 Subject: [PATCH 085/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index d3e6109dc6afe..47b53478538f4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -62,7 +62,7 @@ define HAL_CAN_POOL_SIZE 6000 # BATTERY define HAL_PERIPH_ENABLE_BATTERY -# define AP_BATTERY_ANALOG_ENABLED 1 +define AP_BATTERY_ANALOG_ENABLED 1 define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE From 223421a25dbf16ddee5495cb8ae4c0c0b70de68a Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Fri, 21 Jun 2024 14:38:44 +0300 Subject: [PATCH 086/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 47b53478538f4..c06add7e648ea 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -62,13 +62,13 @@ define HAL_CAN_POOL_SIZE 6000 # BATTERY define HAL_PERIPH_ENABLE_BATTERY -define AP_BATTERY_ANALOG_ENABLED 1 +# define AP_BATTERY_ANALOG_ENABLED 1 define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE PA2 BATT_CURRENT_SENS ADC1 SCALE(1) -define HAL_BATT_MONITOR_DEFAULT 8 +define HAL_BATT_MONITOR_DEFAULT 4 define HAL_BATT_CURR_PIN 2 define HAL_BATT_CURR_SCALE 40.0 From a6c3a282ba2dc7ff64671c4adb037fa2a596eb83 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Fri, 21 Jun 2024 14:49:29 +0300 Subject: [PATCH 087/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index c06add7e648ea..4808f05b8c186 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -67,8 +67,12 @@ define HAL_PERIPH_ENABLE_BATTERY define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE +PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) PA2 BATT_CURRENT_SENS ADC1 SCALE(1) + define HAL_BATT_MONITOR_DEFAULT 4 +define HAL_BATT_VOLT_PIN 1 +define HAL_BATT_VOLT_SCALE 21.0 define HAL_BATT_CURR_PIN 2 define HAL_BATT_CURR_SCALE 40.0 From b74dc4ade1035b7343d283ec6bb9505fcfb19220 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Fri, 21 Jun 2024 15:10:19 +0300 Subject: [PATCH 088/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 4808f05b8c186..7a3664d2803e4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -69,6 +69,7 @@ define STM32_ADC_USE_ADC1 TRUE PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) PA2 BATT_CURRENT_SENS ADC1 SCALE(1) +define AP_TEMPERATURE_SENSOR_ENABLED 1 define HAL_BATT_MONITOR_DEFAULT 4 define HAL_BATT_VOLT_PIN 1 From e2e76f8e8219ea4144fa241049d31f8aeddc0fd5 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Fri, 21 Jun 2024 16:15:32 +0300 Subject: [PATCH 089/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 7a3664d2803e4..9c956ff5eed61 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -69,7 +69,7 @@ define STM32_ADC_USE_ADC1 TRUE PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) PA2 BATT_CURRENT_SENS ADC1 SCALE(1) -define AP_TEMPERATURE_SENSOR_ENABLED 1 +define AP_TEMPERATURE_SENSOR_ANALOG_ENABLED 1 define HAL_BATT_MONITOR_DEFAULT 4 define HAL_BATT_VOLT_PIN 1 From d46b8d130bf0088ec07d7b7ae5922191efa10d56 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Fri, 21 Jun 2024 16:18:31 +0300 Subject: [PATCH 090/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 9c956ff5eed61..7a3664d2803e4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -69,7 +69,7 @@ define STM32_ADC_USE_ADC1 TRUE PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) PA2 BATT_CURRENT_SENS ADC1 SCALE(1) -define AP_TEMPERATURE_SENSOR_ANALOG_ENABLED 1 +define AP_TEMPERATURE_SENSOR_ENABLED 1 define HAL_BATT_MONITOR_DEFAULT 4 define HAL_BATT_VOLT_PIN 1 From 3dc58bfc2e71678e01ed2151e2b22a4f29dc9dc8 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 24 Jun 2024 12:05:37 +0300 Subject: [PATCH 091/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 7a3664d2803e4..5abb8c2a74ccd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -63,6 +63,7 @@ define HAL_CAN_POOL_SIZE 6000 # BATTERY define HAL_PERIPH_ENABLE_BATTERY # define AP_BATTERY_ANALOG_ENABLED 1 +define HAL_WITH_MCU_MONITORING 1 define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE From ef42fdc25547125065c1c001694eed1a765f5abd Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 24 Jun 2024 12:18:14 +0300 Subject: [PATCH 092/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 5abb8c2a74ccd..db231ec87b77c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -63,10 +63,10 @@ define HAL_CAN_POOL_SIZE 6000 # BATTERY define HAL_PERIPH_ENABLE_BATTERY # define AP_BATTERY_ANALOG_ENABLED 1 -define HAL_WITH_MCU_MONITORING 1 define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE +define HAL_WITH_MCU_MONITORING 1 PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) PA2 BATT_CURRENT_SENS ADC1 SCALE(1) From 111af3b3a409e0edeae9dc781825b22d21242e87 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 24 Jun 2024 12:54:06 +0300 Subject: [PATCH 093/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index db231ec87b77c..dc9e107190861 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -66,7 +66,7 @@ define HAL_PERIPH_ENABLE_BATTERY define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE -define HAL_WITH_MCU_MONITORING 1 +define HAL_WITH_MCU_MONITORING PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) PA2 BATT_CURRENT_SENS ADC1 SCALE(1) From 420046aa117c3dab1772c98f39c2c9f8f4b8680d Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 24 Jun 2024 13:11:07 +0300 Subject: [PATCH 094/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index dc9e107190861..827175ab208bd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -66,7 +66,8 @@ define HAL_PERIPH_ENABLE_BATTERY define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE -define HAL_WITH_MCU_MONITORING +define HAL_WITH_MCU_MONITORING 1 +define HAL_ANALOG1_PINS PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) PA2 BATT_CURRENT_SENS ADC1 SCALE(1) From 99ee4405c906fd677e3a4f0989a933e3a4e11040 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 24 Jun 2024 13:42:20 +0300 Subject: [PATCH 095/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 827175ab208bd..44f35a1d4dfbb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -66,11 +66,10 @@ define HAL_PERIPH_ENABLE_BATTERY define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE -define HAL_WITH_MCU_MONITORING 1 -define HAL_ANALOG1_PINS PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) PA2 BATT_CURRENT_SENS ADC1 SCALE(1) +ADC_CHANNEL_TEMPSENSOR BATT_TEMP_SENS ADC1 SCALE(1) define AP_TEMPERATURE_SENSOR_ENABLED 1 define HAL_BATT_MONITOR_DEFAULT 4 From 7e251b48dd54925c769cc2f00e41f00e9d29ca05 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 24 Jun 2024 14:03:56 +0300 Subject: [PATCH 096/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 44f35a1d4dfbb..d6c6eb770215d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -69,7 +69,7 @@ define STM32_ADC_USE_ADC1 TRUE PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) PA2 BATT_CURRENT_SENS ADC1 SCALE(1) -ADC_CHANNEL_TEMPSENSOR BATT_TEMP_SENS ADC1 SCALE(1) + define AP_TEMPERATURE_SENSOR_ENABLED 1 define HAL_BATT_MONITOR_DEFAULT 4 From d5db363ff5118ed529aacf38e3d016f4b571b677 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 24 Jun 2024 14:21:33 +0300 Subject: [PATCH 097/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index d6c6eb770215d..ec1ab7c3f77d6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -69,6 +69,7 @@ define STM32_ADC_USE_ADC1 TRUE PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) PA2 BATT_CURRENT_SENS ADC1 SCALE(1) +PA3 BATT_TEMP_SENS ADC1 SCALE(1) define AP_TEMPERATURE_SENSOR_ENABLED 1 @@ -77,6 +78,7 @@ define HAL_BATT_VOLT_PIN 1 define HAL_BATT_VOLT_SCALE 21.0 define HAL_BATT_CURR_PIN 2 define HAL_BATT_CURR_SCALE 40.0 +define HAL_BATT_TEMP_PIN 3 # bootloader embedding / bootloader flashing not available define AP_BOOTLOADER_FLASHING_ENABLED 0 From b326b2a982bc35e837fa8f1f053ef6c4806b08ae Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 25 Jun 2024 11:33:32 +0300 Subject: [PATCH 098/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index ec1ab7c3f77d6..fe799ce6c447c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -71,7 +71,7 @@ PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) PA2 BATT_CURRENT_SENS ADC1 SCALE(1) PA3 BATT_TEMP_SENS ADC1 SCALE(1) -define AP_TEMPERATURE_SENSOR_ENABLED 1 +# define AP_TEMPERATURE_SENSOR_ENABLED 1 define HAL_BATT_MONITOR_DEFAULT 4 define HAL_BATT_VOLT_PIN 1 From 0ac103927f76dac188ef97d3f7c4302328ee6427 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 25 Jun 2024 12:00:09 +0300 Subject: [PATCH 099/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index fe799ce6c447c..d5b9e3351f305 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -79,6 +79,7 @@ define HAL_BATT_VOLT_SCALE 21.0 define HAL_BATT_CURR_PIN 2 define HAL_BATT_CURR_SCALE 40.0 define HAL_BATT_TEMP_PIN 3 +define HAL_BATT_TEMP_SCALE 10 # bootloader embedding / bootloader flashing not available define AP_BOOTLOADER_FLASHING_ENABLED 0 From 3757c561d8d7208aa1771a7a00fe71a9cd9822b5 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 25 Jun 2024 12:05:34 +0300 Subject: [PATCH 100/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index d5b9e3351f305..daa7ba88a3801 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -71,7 +71,7 @@ PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) PA2 BATT_CURRENT_SENS ADC1 SCALE(1) PA3 BATT_TEMP_SENS ADC1 SCALE(1) -# define AP_TEMPERATURE_SENSOR_ENABLED 1 +define AP_TEMPERATURE_SENSOR_ENABLED 1 define HAL_BATT_MONITOR_DEFAULT 4 define HAL_BATT_VOLT_PIN 1 From bccf09a220ab5a9db2ba1885ecea9f1bbbd2f7eb Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 25 Jun 2024 12:09:15 +0300 Subject: [PATCH 101/143] Update hwdef-bl.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat index 5bddb38ab9d78..5e3b831cfb63c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat @@ -57,7 +57,7 @@ define DMA_RESERVE_SIZE 0 # enable CAN support PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 -# PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW +PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW # make bl baudrate match debug baudrate for easier debugging define BOOTLOADER_BAUDRATE 57600 From 738d0d83b222abe8232ea0ad3f9a9c25e2619c67 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 25 Jun 2024 12:22:49 +0300 Subject: [PATCH 102/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index daa7ba88a3801..e7fe9e1c16df7 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -69,7 +69,7 @@ define STM32_ADC_USE_ADC1 TRUE PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) PA2 BATT_CURRENT_SENS ADC1 SCALE(1) -PA3 BATT_TEMP_SENS ADC1 SCALE(1) +PA4 BATT_TEMP_SENS ADC1 SCALE(1) define AP_TEMPERATURE_SENSOR_ENABLED 1 @@ -78,8 +78,8 @@ define HAL_BATT_VOLT_PIN 1 define HAL_BATT_VOLT_SCALE 21.0 define HAL_BATT_CURR_PIN 2 define HAL_BATT_CURR_SCALE 40.0 -define HAL_BATT_TEMP_PIN 3 -define HAL_BATT_TEMP_SCALE 10 +define HAL_BATT_TEMP_PIN 4 +define HAL_BATT_TEMP_SCALE -1 # bootloader embedding / bootloader flashing not available define AP_BOOTLOADER_FLASHING_ENABLED 0 From d0a19aa34e065ffa3397a4c97e98f7b9cac90d16 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 25 Jun 2024 13:07:19 +0300 Subject: [PATCH 103/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index e7fe9e1c16df7..317fab729a25c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -62,7 +62,6 @@ define HAL_CAN_POOL_SIZE 6000 # BATTERY define HAL_PERIPH_ENABLE_BATTERY -# define AP_BATTERY_ANALOG_ENABLED 1 define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE @@ -72,14 +71,15 @@ PA2 BATT_CURRENT_SENS ADC1 SCALE(1) PA4 BATT_TEMP_SENS ADC1 SCALE(1) define AP_TEMPERATURE_SENSOR_ENABLED 1 +define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 1 define HAL_BATT_MONITOR_DEFAULT 4 define HAL_BATT_VOLT_PIN 1 define HAL_BATT_VOLT_SCALE 21.0 define HAL_BATT_CURR_PIN 2 define HAL_BATT_CURR_SCALE 40.0 -define HAL_BATT_TEMP_PIN 4 -define HAL_BATT_TEMP_SCALE -1 + +define AP_SCRIPTING_ENABLED 1 # bootloader embedding / bootloader flashing not available define AP_BOOTLOADER_FLASHING_ENABLED 0 From 9a14d5aac80af65e7a83c87d9cdee7725206ffc0 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 25 Jun 2024 13:08:20 +0300 Subject: [PATCH 104/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 -- 1 file changed, 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 317fab729a25c..ed7662d66ed88 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -79,7 +79,5 @@ define HAL_BATT_VOLT_SCALE 21.0 define HAL_BATT_CURR_PIN 2 define HAL_BATT_CURR_SCALE 40.0 -define AP_SCRIPTING_ENABLED 1 - # bootloader embedding / bootloader flashing not available define AP_BOOTLOADER_FLASHING_ENABLED 0 From d7a9b09e0e2917c10c38ba3acf80405e3c01ccc2 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 25 Jun 2024 13:17:34 +0300 Subject: [PATCH 105/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index ed7662d66ed88..606675c72607d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -68,7 +68,7 @@ define STM32_ADC_USE_ADC1 TRUE PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) PA2 BATT_CURRENT_SENS ADC1 SCALE(1) -PA4 BATT_TEMP_SENS ADC1 SCALE(1) +PA3 BATT_TEMP_SENS ADC1 SCALE(1) define AP_TEMPERATURE_SENSOR_ENABLED 1 define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 1 From b98782d3d274e3292aaac776a6d53299a0dfe1f1 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 25 Jun 2024 13:25:28 +0300 Subject: [PATCH 106/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 606675c72607d..b1f13102ece56 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -79,5 +79,7 @@ define HAL_BATT_VOLT_SCALE 21.0 define HAL_BATT_CURR_PIN 2 define HAL_BATT_CURR_SCALE 40.0 +define AP_BATTERY_SCRIPTING_ENABLED 1 + # bootloader embedding / bootloader flashing not available define AP_BOOTLOADER_FLASHING_ENABLED 0 From 176c55f71e45ded7dfc91520a5912bea5fc06c18 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 25 Jun 2024 13:36:19 +0300 Subject: [PATCH 107/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index b1f13102ece56..c4bd2e41a26f4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -66,15 +66,15 @@ define HAL_PERIPH_ENABLE_BATTERY define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE -PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PA3 BATT_VOLTAGE_SENS ADC1 SCALE(1) PA2 BATT_CURRENT_SENS ADC1 SCALE(1) -PA3 BATT_TEMP_SENS ADC1 SCALE(1) +PA1 BATT_TEMP_SENS ADC1 SCALE(1) define AP_TEMPERATURE_SENSOR_ENABLED 1 define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 1 define HAL_BATT_MONITOR_DEFAULT 4 -define HAL_BATT_VOLT_PIN 1 +define HAL_BATT_VOLT_PIN 3 define HAL_BATT_VOLT_SCALE 21.0 define HAL_BATT_CURR_PIN 2 define HAL_BATT_CURR_SCALE 40.0 From 5c20d067ba68a2e5213b97ca3d5126d1baf2ad9b Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 25 Jun 2024 13:58:31 +0300 Subject: [PATCH 108/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index c4bd2e41a26f4..dab244832495c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -66,15 +66,15 @@ define HAL_PERIPH_ENABLE_BATTERY define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE -PA3 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) PA2 BATT_CURRENT_SENS ADC1 SCALE(1) -PA1 BATT_TEMP_SENS ADC1 SCALE(1) +# PA3 BATT_TEMP_SENS ADC1 SCALE(1) define AP_TEMPERATURE_SENSOR_ENABLED 1 define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 1 define HAL_BATT_MONITOR_DEFAULT 4 -define HAL_BATT_VOLT_PIN 3 +define HAL_BATT_VOLT_PIN 1 define HAL_BATT_VOLT_SCALE 21.0 define HAL_BATT_CURR_PIN 2 define HAL_BATT_CURR_SCALE 40.0 From 82cbc8bb18f18573bf9badc87bc51dffa8b79934 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 25 Jun 2024 14:03:42 +0300 Subject: [PATCH 109/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index dab244832495c..b1f13102ece56 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -68,7 +68,7 @@ define STM32_ADC_USE_ADC1 TRUE PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) PA2 BATT_CURRENT_SENS ADC1 SCALE(1) -# PA3 BATT_TEMP_SENS ADC1 SCALE(1) +PA3 BATT_TEMP_SENS ADC1 SCALE(1) define AP_TEMPERATURE_SENSOR_ENABLED 1 define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 1 From 0d682bad78cd1b91022ea324368860118af5bf50 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 5 Nov 2024 10:05:37 +0300 Subject: [PATCH 110/143] Update hwdef-bl.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat index 5e3b831cfb63c..61e2b5cea4c15 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat @@ -16,7 +16,7 @@ APJ_BOARD_ID 1001 env AP_PERIPH 1 # crystal frequency -OSCILLATOR_HZ 16000000 +OSCILLATOR_HZ 8000000 define CH_CFG_ST_FREQUENCY 1000000 From 2b9a2dff73f2085192e4d9d62059da5e48beb0bc Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Tue, 5 Nov 2024 10:06:05 +0300 Subject: [PATCH 111/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index b1f13102ece56..5bfb065003fe1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -22,7 +22,7 @@ STM32_ST_USE_TIMER 5 # enable watchdog # crystal frequency -OSCILLATOR_HZ 16000000 +OSCILLATOR_HZ 8000000 define CH_CFG_ST_FREQUENCY 1000000 From 6a265a8020f8d03d964426f7c2cc2e63ac256dbf Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 11 Nov 2024 16:34:08 +0300 Subject: [PATCH 112/143] Create hwdef_INA239 --- .../hwdef/Inferno-PMU/hwdef_INA239 | 78 +++++++++++++++++++ 1 file changed, 78 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef_INA239 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef_INA239 b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef_INA239 new file mode 100644 index 0000000000000..e96dcc6d8009b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef_INA239 @@ -0,0 +1,78 @@ +# hw definition file for processing by chibios_pins.py +# MCU class and specific type + +# MCU class and specific type +MCU STM32F4xx STM32F412Rx + +# bootloader starts firmware at 64k +FLASH_RESERVE_START_KB 64 + +# store parameters in pages 2 and 3 +STORAGE_FLASH_PAGE 2 +define HAL_STORAGE_SIZE 8192 + +# board ID for firmware load +APJ_BOARD_ID 1001 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +STM32_ST_USE_TIMER 5 + +# enable watchdog + +# crystal frequency +OSCILLATOR_HZ 8000000 + +define CH_CFG_ST_FREQUENCY 1000000 + +# assume 512k flash part +FLASH_SIZE_KB 512 + +define HAL_NO_GPIO_IRQ +define SERIAL_BUFFERS_SIZE 512 +define PORT_INT_REQUIRED_STACK 64 + +define DMA_RESERVE_SIZE 0 + +define HAL_NO_MONITOR_THREAD + +# we setup a small defaults.parm +define AP_PARAM_MAX_EMBEDDED_PARAM 512 + +# order of UARTs +SERIAL_ORDER USART1 EMPTY EMPTY EMPTY + +# USART1 for debug +PB6 USART1_TX USART1 NODMA +PB7 USART1_RX USART1 NODMA +define DEFAULT_SERIAL0_BAUD 57600 + +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +#CAN bus +CAN_ORDER 1 +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 +PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +define HAL_CAN_POOL_SIZE 6000 + +# enable battery monitor +define HAL_PERIPH_ENABLE_BATTERY +define AP_BATTERY_INA239_ENABLED 1 +define AP_BATTERY_INA239_SPI_DEVICE "INA23X" +define HAL_BATT_MONITOR_DEFAULT 26 +define AP_PERIPH_BATTERY_MODEL_NAME "MatekL431-BattMon" + +SPIDEV INA23X SPI1 DEVID1 SPARE_CS MODE1 10*MHZ 10*MHZ + +# no ADC pins +define HAL_USE_ADC FALSE + +define AP_BATTERY_SCRIPTING_ENABLED 1 + +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 From 867b4526a2ea1700576af49ce62d0d7227c5edf3 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 11 Nov 2024 16:34:31 +0300 Subject: [PATCH 113/143] Rename hwdef_INA239 to hwdef_INA239.dat --- .../hwdef/Inferno-PMU/{hwdef_INA239 => hwdef_INA239.dat} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/{hwdef_INA239 => hwdef_INA239.dat} (100%) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef_INA239 b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef_INA239.dat similarity index 100% rename from libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef_INA239 rename to libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef_INA239.dat From cff35c9fde87d6fa0e214383008c4ad23971e9bf Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 11 Nov 2024 16:35:35 +0300 Subject: [PATCH 114/143] Rename hwdef.dat to hwdef_old.dat --- .../AP_HAL_ChibiOS/hwdef/Inferno-PMU/{hwdef.dat => hwdef_old.dat} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/{hwdef.dat => hwdef_old.dat} (100%) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef_old.dat similarity index 100% rename from libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat rename to libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef_old.dat From dc4cd0542e21ae1ffb520c6ec8de536639c4adf9 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 11 Nov 2024 16:35:52 +0300 Subject: [PATCH 115/143] Rename hwdef_INA239.dat to hwdef.dat --- .../hwdef/Inferno-PMU/{hwdef_INA239.dat => hwdef.dat} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/{hwdef_INA239.dat => hwdef.dat} (100%) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef_INA239.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat similarity index 100% rename from libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef_INA239.dat rename to libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat From fb7953821f593aead81068c75d0aa611a0defeca Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 11 Nov 2024 16:39:15 +0300 Subject: [PATCH 116/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index e96dcc6d8009b..1331bca1307e6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -58,6 +58,12 @@ PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW +# --------------------- SPI1 RM3100 ----------------------- +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PA4 SPARE_CS CS + define HAL_CAN_POOL_SIZE 6000 # enable battery monitor From eb9a888e056b58972ac67fef23e0d76d1c6245f0 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 11 Nov 2024 16:48:15 +0300 Subject: [PATCH 117/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 1331bca1307e6..3c80a190609b3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -67,6 +67,9 @@ PA4 SPARE_CS CS define HAL_CAN_POOL_SIZE 6000 # enable battery monitor +define AP_TEMPERATURE_SENSOR_ENABLED 1 +define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 1 + define HAL_PERIPH_ENABLE_BATTERY define AP_BATTERY_INA239_ENABLED 1 define AP_BATTERY_INA239_SPI_DEVICE "INA23X" From 6bd933620a72eb92784e43ba4571e55e18ca7766 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 11 Nov 2024 16:55:02 +0300 Subject: [PATCH 118/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 3c80a190609b3..849b9b288b6c0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -67,8 +67,8 @@ PA4 SPARE_CS CS define HAL_CAN_POOL_SIZE 6000 # enable battery monitor -define AP_TEMPERATURE_SENSOR_ENABLED 1 -define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 1 +#define AP_TEMPERATURE_SENSOR_ENABLED 1 +#define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 1 define HAL_PERIPH_ENABLE_BATTERY define AP_BATTERY_INA239_ENABLED 1 From e39c3dc7ae68376b6a3673720195277acd8391cb Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Mon, 11 Nov 2024 17:03:51 +0300 Subject: [PATCH 119/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 849b9b288b6c0..3c80a190609b3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -67,8 +67,8 @@ PA4 SPARE_CS CS define HAL_CAN_POOL_SIZE 6000 # enable battery monitor -#define AP_TEMPERATURE_SENSOR_ENABLED 1 -#define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 1 +define AP_TEMPERATURE_SENSOR_ENABLED 1 +define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 1 define HAL_PERIPH_ENABLE_BATTERY define AP_BATTERY_INA239_ENABLED 1 From 205878e65f275b808f72ed7b6f24f80283227b66 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 13 Nov 2024 14:57:20 +0300 Subject: [PATCH 120/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 3c80a190609b3..091677f946588 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -52,6 +52,9 @@ define DEFAULT_SERIAL0_BAUD 57600 PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD +PB13 LED OUTPUT HIGH +define HAL_LED_ON 1 + #CAN bus CAN_ORDER 1 PB8 CAN1_RX CAN1 From 43fc9981ba69f8755a8b8ac22ba336d7071fce72 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 13 Nov 2024 15:14:19 +0300 Subject: [PATCH 121/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 091677f946588..b1d50558d8121 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -52,7 +52,7 @@ define DEFAULT_SERIAL0_BAUD 57600 PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -PB13 LED OUTPUT HIGH +PB14 LED OUTPUT HIGH define HAL_LED_ON 1 #CAN bus From 86a64dec69b557ea1c6f503324607cdc481a90e1 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 13 Nov 2024 15:35:14 +0300 Subject: [PATCH 122/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index b1d50558d8121..0bcce04e5c82b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -77,7 +77,7 @@ define HAL_PERIPH_ENABLE_BATTERY define AP_BATTERY_INA239_ENABLED 1 define AP_BATTERY_INA239_SPI_DEVICE "INA23X" define HAL_BATT_MONITOR_DEFAULT 26 -define AP_PERIPH_BATTERY_MODEL_NAME "MatekL431-BattMon" +define AP_PERIPH_BATTERY_MODEL_NAME "Inferno-PMU" SPIDEV INA23X SPI1 DEVID1 SPARE_CS MODE1 10*MHZ 10*MHZ From d40f862ab8cdd713c331e956fb76225c99311d41 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 14 Nov 2024 13:12:06 +0300 Subject: [PATCH 123/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 0bcce04e5c82b..da9295f767999 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -72,6 +72,7 @@ define HAL_CAN_POOL_SIZE 6000 # enable battery monitor define AP_TEMPERATURE_SENSOR_ENABLED 1 define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 1 +define HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE define HAL_PERIPH_ENABLE_BATTERY define AP_BATTERY_INA239_ENABLED 1 From 1c8e7b4589ac9c12ece21a781fa89970030216c0 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 14 Nov 2024 13:22:00 +0300 Subject: [PATCH 124/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index da9295f767999..44b81bbc3db7d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -82,8 +82,8 @@ define AP_PERIPH_BATTERY_MODEL_NAME "Inferno-PMU" SPIDEV INA23X SPI1 DEVID1 SPARE_CS MODE1 10*MHZ 10*MHZ -# no ADC pins -define HAL_USE_ADC FALSE +# ADC pins +define HAL_USE_ADC TRUE define AP_BATTERY_SCRIPTING_ENABLED 1 From 78d49000e495921ea98345810c41d823562d3f8e Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 14 Nov 2024 13:22:56 +0300 Subject: [PATCH 125/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat index 44b81bbc3db7d..9026aedfbdd61 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat @@ -83,7 +83,7 @@ define AP_PERIPH_BATTERY_MODEL_NAME "Inferno-PMU" SPIDEV INA23X SPI1 DEVID1 SPARE_CS MODE1 10*MHZ 10*MHZ # ADC pins -define HAL_USE_ADC TRUE +define HAL_USE_ADC FALSE define AP_BATTERY_SCRIPTING_ENABLED 1 From 7ad09c0f9b7e8737dee80856f66692532adb4192 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 14 Nov 2024 13:41:38 +0300 Subject: [PATCH 126/143] Create hwdef.dat --- .../AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat | 91 +++++++++++++++++++ 1 file changed, 91 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat new file mode 100644 index 0000000000000..9026aedfbdd61 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat @@ -0,0 +1,91 @@ +# hw definition file for processing by chibios_pins.py +# MCU class and specific type + +# MCU class and specific type +MCU STM32F4xx STM32F412Rx + +# bootloader starts firmware at 64k +FLASH_RESERVE_START_KB 64 + +# store parameters in pages 2 and 3 +STORAGE_FLASH_PAGE 2 +define HAL_STORAGE_SIZE 8192 + +# board ID for firmware load +APJ_BOARD_ID 1001 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +STM32_ST_USE_TIMER 5 + +# enable watchdog + +# crystal frequency +OSCILLATOR_HZ 8000000 + +define CH_CFG_ST_FREQUENCY 1000000 + +# assume 512k flash part +FLASH_SIZE_KB 512 + +define HAL_NO_GPIO_IRQ +define SERIAL_BUFFERS_SIZE 512 +define PORT_INT_REQUIRED_STACK 64 + +define DMA_RESERVE_SIZE 0 + +define HAL_NO_MONITOR_THREAD + +# we setup a small defaults.parm +define AP_PARAM_MAX_EMBEDDED_PARAM 512 + +# order of UARTs +SERIAL_ORDER USART1 EMPTY EMPTY EMPTY + +# USART1 for debug +PB6 USART1_TX USART1 NODMA +PB7 USART1_RX USART1 NODMA +define DEFAULT_SERIAL0_BAUD 57600 + +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +PB14 LED OUTPUT HIGH +define HAL_LED_ON 1 + +#CAN bus +CAN_ORDER 1 +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 +PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +# --------------------- SPI1 RM3100 ----------------------- +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PA4 SPARE_CS CS + +define HAL_CAN_POOL_SIZE 6000 + +# enable battery monitor +define AP_TEMPERATURE_SENSOR_ENABLED 1 +define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 1 +define HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE + +define HAL_PERIPH_ENABLE_BATTERY +define AP_BATTERY_INA239_ENABLED 1 +define AP_BATTERY_INA239_SPI_DEVICE "INA23X" +define HAL_BATT_MONITOR_DEFAULT 26 +define AP_PERIPH_BATTERY_MODEL_NAME "Inferno-PMU" + +SPIDEV INA23X SPI1 DEVID1 SPARE_CS MODE1 10*MHZ 10*MHZ + +# ADC pins +define HAL_USE_ADC FALSE + +define AP_BATTERY_SCRIPTING_ENABLED 1 + +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 From ff64453997b6d6ae847b53fcd7fc2f8a06f28234 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 14 Nov 2024 13:42:24 +0300 Subject: [PATCH 127/143] Create hwdef-bl.dat --- .../hwdef/CSKY-PMU/hwdef-bl.dat | 70 +++++++++++++++++++ 1 file changed, 70 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef-bl.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef-bl.dat new file mode 100644 index 0000000000000..61e2b5cea4c15 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef-bl.dat @@ -0,0 +1,70 @@ +# hw definition file for processing by chibios_pins.py + +# Inferno-PMU Bootloader + +# MCU class and specific type +MCU STM32F4xx STM32F412Rx + +FLASH_RESERVE_START_KB 0 +# two sectors for bootloader, two for storage +FLASH_BOOTLOADER_LOAD_KB 64 + +# board ID for firmware load +APJ_BOARD_ID 1001 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +define CH_CFG_ST_FREQUENCY 1000000 + +# Flash available +FLASH_SIZE_KB 512 + +STDOUT_SERIAL SD1 +STDOUT_BAUDRATE 57600 + +# order of UARTs +SERIAL_ORDER + +PB12 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 1 + +# USART1 +PB6 USART1_TX USART1 +PB7 USART1_RX USART1 + +# SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +define HAL_USE_SERIAL TRUE + +define STM32_SERIAL_USE_USART1 TRUE +define STM32_SERIAL_USE_USART2 FALSE +define STM32_SERIAL_USE_USART3 FALSE + +define HAL_NO_GPIO_IRQ +define HAL_USE_EMPTY_IO TRUE + +# avoid timer thread to save memory +define HAL_NO_TIMER_THREAD + +define DMA_RESERVE_SIZE 0 + +# enable CAN support +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 +PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +# make bl baudrate match debug baudrate for easier debugging +define BOOTLOADER_BAUDRATE 57600 + +# use a small bootloader timeout +define HAL_BOOTLOADER_TIMEOUT 1000 + +# Add CS pins to ensure they are high in bootloader +PA4 MAG_CS CS +PA10 MS5611_CS CS From 4db700fb7b0b43ae6e16e52d88a896c1b3670ef3 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 14 Nov 2024 13:42:58 +0300 Subject: [PATCH 128/143] Create hwdef_old.dat --- .../hwdef/CSKY-PMU/hwdef_old.dat | 85 +++++++++++++++++++ 1 file changed, 85 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef_old.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef_old.dat b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef_old.dat new file mode 100644 index 0000000000000..5bfb065003fe1 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef_old.dat @@ -0,0 +1,85 @@ +# hw definition file for processing by chibios_pins.py +# MCU class and specific type + +# MCU class and specific type +MCU STM32F4xx STM32F412Rx + +# bootloader starts firmware at 64k +FLASH_RESERVE_START_KB 64 + +# store parameters in pages 2 and 3 +STORAGE_FLASH_PAGE 2 +define HAL_STORAGE_SIZE 8192 + +# board ID for firmware load +APJ_BOARD_ID 1001 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +STM32_ST_USE_TIMER 5 + +# enable watchdog + +# crystal frequency +OSCILLATOR_HZ 8000000 + +define CH_CFG_ST_FREQUENCY 1000000 + +# assume 512k flash part +FLASH_SIZE_KB 512 + +define HAL_NO_GPIO_IRQ +define SERIAL_BUFFERS_SIZE 512 +define PORT_INT_REQUIRED_STACK 64 + +define DMA_RESERVE_SIZE 0 + +define HAL_NO_MONITOR_THREAD + +# we setup a small defaults.parm +define AP_PARAM_MAX_EMBEDDED_PARAM 512 + +# order of UARTs +SERIAL_ORDER USART1 EMPTY EMPTY EMPTY + +# USART1 for debug +PB6 USART1_TX USART1 NODMA +PB7 USART1_RX USART1 NODMA +define DEFAULT_SERIAL0_BAUD 57600 + +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +#CAN bus +CAN_ORDER 1 +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 +PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +define HAL_CAN_POOL_SIZE 6000 + +# BATTERY +define HAL_PERIPH_ENABLE_BATTERY + +define HAL_USE_ADC TRUE +define STM32_ADC_USE_ADC1 TRUE + +PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PA2 BATT_CURRENT_SENS ADC1 SCALE(1) +PA3 BATT_TEMP_SENS ADC1 SCALE(1) + +define AP_TEMPERATURE_SENSOR_ENABLED 1 +define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 1 + +define HAL_BATT_MONITOR_DEFAULT 4 +define HAL_BATT_VOLT_PIN 1 +define HAL_BATT_VOLT_SCALE 21.0 +define HAL_BATT_CURR_PIN 2 +define HAL_BATT_CURR_SCALE 40.0 + +define AP_BATTERY_SCRIPTING_ENABLED 1 + +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 From 00e61bd493eddcb093000864d416a8225236d993 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 14 Nov 2024 13:43:37 +0300 Subject: [PATCH 129/143] Delete libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU directory --- .../hwdef/Inferno-PMU/hwdef-bl.dat | 70 -------------- .../hwdef/Inferno-PMU/hwdef.dat | 91 ------------------- .../hwdef/Inferno-PMU/hwdef_old.dat | 85 ----------------- 3 files changed, 246 deletions(-) delete mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat delete mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat delete mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef_old.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat deleted file mode 100644 index 61e2b5cea4c15..0000000000000 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef-bl.dat +++ /dev/null @@ -1,70 +0,0 @@ -# hw definition file for processing by chibios_pins.py - -# Inferno-PMU Bootloader - -# MCU class and specific type -MCU STM32F4xx STM32F412Rx - -FLASH_RESERVE_START_KB 0 -# two sectors for bootloader, two for storage -FLASH_BOOTLOADER_LOAD_KB 64 - -# board ID for firmware load -APJ_BOARD_ID 1001 - -# setup build for a peripheral firmware -env AP_PERIPH 1 - -# crystal frequency -OSCILLATOR_HZ 8000000 - -define CH_CFG_ST_FREQUENCY 1000000 - -# Flash available -FLASH_SIZE_KB 512 - -STDOUT_SERIAL SD1 -STDOUT_BAUDRATE 57600 - -# order of UARTs -SERIAL_ORDER - -PB12 LED_BOOTLOADER OUTPUT LOW -define HAL_LED_ON 1 - -# USART1 -PB6 USART1_TX USART1 -PB7 USART1_RX USART1 - -# SWD debugging -PA13 JTMS-SWDIO SWD -PA14 JTCK-SWCLK SWD - -define HAL_USE_SERIAL TRUE - -define STM32_SERIAL_USE_USART1 TRUE -define STM32_SERIAL_USE_USART2 FALSE -define STM32_SERIAL_USE_USART3 FALSE - -define HAL_NO_GPIO_IRQ -define HAL_USE_EMPTY_IO TRUE - -# avoid timer thread to save memory -define HAL_NO_TIMER_THREAD - -define DMA_RESERVE_SIZE 0 - -# enable CAN support -PB8 CAN1_RX CAN1 -PB9 CAN1_TX CAN1 -PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW - -# make bl baudrate match debug baudrate for easier debugging -define BOOTLOADER_BAUDRATE 57600 - -# use a small bootloader timeout -define HAL_BOOTLOADER_TIMEOUT 1000 - -# Add CS pins to ensure they are high in bootloader -PA4 MAG_CS CS -PA10 MS5611_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat deleted file mode 100644 index 9026aedfbdd61..0000000000000 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef.dat +++ /dev/null @@ -1,91 +0,0 @@ -# hw definition file for processing by chibios_pins.py -# MCU class and specific type - -# MCU class and specific type -MCU STM32F4xx STM32F412Rx - -# bootloader starts firmware at 64k -FLASH_RESERVE_START_KB 64 - -# store parameters in pages 2 and 3 -STORAGE_FLASH_PAGE 2 -define HAL_STORAGE_SIZE 8192 - -# board ID for firmware load -APJ_BOARD_ID 1001 - -# setup build for a peripheral firmware -env AP_PERIPH 1 - -STM32_ST_USE_TIMER 5 - -# enable watchdog - -# crystal frequency -OSCILLATOR_HZ 8000000 - -define CH_CFG_ST_FREQUENCY 1000000 - -# assume 512k flash part -FLASH_SIZE_KB 512 - -define HAL_NO_GPIO_IRQ -define SERIAL_BUFFERS_SIZE 512 -define PORT_INT_REQUIRED_STACK 64 - -define DMA_RESERVE_SIZE 0 - -define HAL_NO_MONITOR_THREAD - -# we setup a small defaults.parm -define AP_PARAM_MAX_EMBEDDED_PARAM 512 - -# order of UARTs -SERIAL_ORDER USART1 EMPTY EMPTY EMPTY - -# USART1 for debug -PB6 USART1_TX USART1 NODMA -PB7 USART1_RX USART1 NODMA -define DEFAULT_SERIAL0_BAUD 57600 - -# debugger support -PA13 JTMS-SWDIO SWD -PA14 JTCK-SWCLK SWD - -PB14 LED OUTPUT HIGH -define HAL_LED_ON 1 - -#CAN bus -CAN_ORDER 1 -PB8 CAN1_RX CAN1 -PB9 CAN1_TX CAN1 -PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW - -# --------------------- SPI1 RM3100 ----------------------- -PA5 SPI1_SCK SPI1 -PA6 SPI1_MISO SPI1 -PA7 SPI1_MOSI SPI1 -PA4 SPARE_CS CS - -define HAL_CAN_POOL_SIZE 6000 - -# enable battery monitor -define AP_TEMPERATURE_SENSOR_ENABLED 1 -define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 1 -define HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE - -define HAL_PERIPH_ENABLE_BATTERY -define AP_BATTERY_INA239_ENABLED 1 -define AP_BATTERY_INA239_SPI_DEVICE "INA23X" -define HAL_BATT_MONITOR_DEFAULT 26 -define AP_PERIPH_BATTERY_MODEL_NAME "Inferno-PMU" - -SPIDEV INA23X SPI1 DEVID1 SPARE_CS MODE1 10*MHZ 10*MHZ - -# ADC pins -define HAL_USE_ADC FALSE - -define AP_BATTERY_SCRIPTING_ENABLED 1 - -# bootloader embedding / bootloader flashing not available -define AP_BOOTLOADER_FLASHING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef_old.dat b/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef_old.dat deleted file mode 100644 index 5bfb065003fe1..0000000000000 --- a/libraries/AP_HAL_ChibiOS/hwdef/Inferno-PMU/hwdef_old.dat +++ /dev/null @@ -1,85 +0,0 @@ -# hw definition file for processing by chibios_pins.py -# MCU class and specific type - -# MCU class and specific type -MCU STM32F4xx STM32F412Rx - -# bootloader starts firmware at 64k -FLASH_RESERVE_START_KB 64 - -# store parameters in pages 2 and 3 -STORAGE_FLASH_PAGE 2 -define HAL_STORAGE_SIZE 8192 - -# board ID for firmware load -APJ_BOARD_ID 1001 - -# setup build for a peripheral firmware -env AP_PERIPH 1 - -STM32_ST_USE_TIMER 5 - -# enable watchdog - -# crystal frequency -OSCILLATOR_HZ 8000000 - -define CH_CFG_ST_FREQUENCY 1000000 - -# assume 512k flash part -FLASH_SIZE_KB 512 - -define HAL_NO_GPIO_IRQ -define SERIAL_BUFFERS_SIZE 512 -define PORT_INT_REQUIRED_STACK 64 - -define DMA_RESERVE_SIZE 0 - -define HAL_NO_MONITOR_THREAD - -# we setup a small defaults.parm -define AP_PARAM_MAX_EMBEDDED_PARAM 512 - -# order of UARTs -SERIAL_ORDER USART1 EMPTY EMPTY EMPTY - -# USART1 for debug -PB6 USART1_TX USART1 NODMA -PB7 USART1_RX USART1 NODMA -define DEFAULT_SERIAL0_BAUD 57600 - -# debugger support -PA13 JTMS-SWDIO SWD -PA14 JTCK-SWCLK SWD - -#CAN bus -CAN_ORDER 1 -PB8 CAN1_RX CAN1 -PB9 CAN1_TX CAN1 -PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW - -define HAL_CAN_POOL_SIZE 6000 - -# BATTERY -define HAL_PERIPH_ENABLE_BATTERY - -define HAL_USE_ADC TRUE -define STM32_ADC_USE_ADC1 TRUE - -PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) -PA2 BATT_CURRENT_SENS ADC1 SCALE(1) -PA3 BATT_TEMP_SENS ADC1 SCALE(1) - -define AP_TEMPERATURE_SENSOR_ENABLED 1 -define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 1 - -define HAL_BATT_MONITOR_DEFAULT 4 -define HAL_BATT_VOLT_PIN 1 -define HAL_BATT_VOLT_SCALE 21.0 -define HAL_BATT_CURR_PIN 2 -define HAL_BATT_CURR_SCALE 40.0 - -define AP_BATTERY_SCRIPTING_ENABLED 1 - -# bootloader embedding / bootloader flashing not available -define AP_BOOTLOADER_FLASHING_ENABLED 0 From 3c93ef5027ae654a76f04deec8216d9f4a6f6639 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Thu, 14 Nov 2024 15:28:27 +0300 Subject: [PATCH 130/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat index 9026aedfbdd61..f09bbc1581fb6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat @@ -74,6 +74,11 @@ define AP_TEMPERATURE_SENSOR_ENABLED 1 define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 1 define HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE +define HAL_USE_ADC TRUE +define STM32_ADC_USE_ADC1 TRUE + +PA3 BATT_TEMP_SENS ADC1 SCALE(1) + define HAL_PERIPH_ENABLE_BATTERY define AP_BATTERY_INA239_ENABLED 1 define AP_BATTERY_INA239_SPI_DEVICE "INA23X" @@ -83,7 +88,7 @@ define AP_PERIPH_BATTERY_MODEL_NAME "Inferno-PMU" SPIDEV INA23X SPI1 DEVID1 SPARE_CS MODE1 10*MHZ 10*MHZ # ADC pins -define HAL_USE_ADC FALSE +№define HAL_USE_ADC FALSE define AP_BATTERY_SCRIPTING_ENABLED 1 From 9ed5f7ed64b121399082b0e12d33ff77e25311fb Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Fri, 15 Nov 2024 10:45:19 +0300 Subject: [PATCH 131/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat index f09bbc1581fb6..b51ec47023dba 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat @@ -83,7 +83,7 @@ define HAL_PERIPH_ENABLE_BATTERY define AP_BATTERY_INA239_ENABLED 1 define AP_BATTERY_INA239_SPI_DEVICE "INA23X" define HAL_BATT_MONITOR_DEFAULT 26 -define AP_PERIPH_BATTERY_MODEL_NAME "Inferno-PMU" +define CAN_APP_NODE_NAME "org.csky.pmu" SPIDEV INA23X SPI1 DEVID1 SPARE_CS MODE1 10*MHZ 10*MHZ From db9ea5391f0039b2715da09562fc2bc0aea2fa65 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Fri, 15 Nov 2024 10:45:34 +0300 Subject: [PATCH 132/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat index b51ec47023dba..c594ffea73511 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat @@ -88,7 +88,7 @@ define CAN_APP_NODE_NAME "org.csky.pmu" SPIDEV INA23X SPI1 DEVID1 SPARE_CS MODE1 10*MHZ 10*MHZ # ADC pins -№define HAL_USE_ADC FALSE +#define HAL_USE_ADC FALSE define AP_BATTERY_SCRIPTING_ENABLED 1 From 42df5002e0751c68ab933c9337aefb1f4f42c7f9 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Fri, 15 Nov 2024 11:17:29 +0300 Subject: [PATCH 133/143] Create defaults.parm --- libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/defaults.parm | 1 + 1 file changed, 1 insertion(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/defaults.parm new file mode 100644 index 0000000000000..8b137891791fe --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/defaults.parm @@ -0,0 +1 @@ + From 6ae91afb7b5f1c7a19d5c24b90149d3bb36c8213 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Fri, 15 Nov 2024 11:23:36 +0300 Subject: [PATCH 134/143] Update hwdef-bl.dat --- .../AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef-bl.dat | 18 ++++++++---------- 1 file changed, 8 insertions(+), 10 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef-bl.dat index 61e2b5cea4c15..a5b6ea37050b8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef-bl.dat @@ -1,23 +1,25 @@ # hw definition file for processing by chibios_pins.py -# Inferno-PMU Bootloader +# CSKY-PMU Bootloader # MCU class and specific type MCU STM32F4xx STM32F412Rx +# bootloader loads at start of flash FLASH_RESERVE_START_KB 0 -# two sectors for bootloader, two for storage + +# location of application code FLASH_BOOTLOADER_LOAD_KB 64 # board ID for firmware load APJ_BOARD_ID 1001 -# setup build for a peripheral firmware -env AP_PERIPH 1 - # crystal frequency OSCILLATOR_HZ 8000000 +# setup build for a peripheral firmware +env AP_PERIPH 1 + define CH_CFG_ST_FREQUENCY 1000000 # Flash available @@ -29,7 +31,7 @@ STDOUT_BAUDRATE 57600 # order of UARTs SERIAL_ORDER -PB12 LED_BOOTLOADER OUTPUT LOW +PB14 LED_BOOTLOADER OUTPUT HIGH define HAL_LED_ON 1 # USART1 @@ -64,7 +66,3 @@ define BOOTLOADER_BAUDRATE 57600 # use a small bootloader timeout define HAL_BOOTLOADER_TIMEOUT 1000 - -# Add CS pins to ensure they are high in bootloader -PA4 MAG_CS CS -PA10 MS5611_CS CS From 26868d4d146d77cad888ab334ae1f9644c122745 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Fri, 15 Nov 2024 11:25:11 +0300 Subject: [PATCH 135/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat index c594ffea73511..276603dd32754 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat @@ -1,5 +1,4 @@ # hw definition file for processing by chibios_pins.py -# MCU class and specific type # MCU class and specific type MCU STM32F4xx STM32F412Rx From 1dd7707bb8f5952b66bbe8166b8eea05ca684e9b Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Fri, 15 Nov 2024 11:26:47 +0300 Subject: [PATCH 136/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat index 276603dd32754..70997c0944086 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat @@ -16,10 +16,9 @@ APJ_BOARD_ID 1001 # setup build for a peripheral firmware env AP_PERIPH 1 +# ChibiOS system timer STM32_ST_USE_TIMER 5 -# enable watchdog - # crystal frequency OSCILLATOR_HZ 8000000 From 8fe2ddf9e07010a8adf910f8798fc19ffad245f0 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Fri, 15 Nov 2024 11:28:32 +0300 Subject: [PATCH 137/143] Update hwdef-bl.dat --- libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef-bl.dat | 3 --- 1 file changed, 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef-bl.dat index a5b6ea37050b8..175b526608249 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef-bl.dat @@ -25,9 +25,6 @@ define CH_CFG_ST_FREQUENCY 1000000 # Flash available FLASH_SIZE_KB 512 -STDOUT_SERIAL SD1 -STDOUT_BAUDRATE 57600 - # order of UARTs SERIAL_ORDER From ab7b928daf9618d39616b0d3f71b50b8fe3d7924 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Fri, 15 Nov 2024 11:44:17 +0300 Subject: [PATCH 138/143] Update hwdef.dat --- .../AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat | 23 ++++++++----------- 1 file changed, 10 insertions(+), 13 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat index 70997c0944086..624bf58e9e6fa 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat @@ -35,7 +35,7 @@ define DMA_RESERVE_SIZE 0 define HAL_NO_MONITOR_THREAD -# we setup a small defaults.parm +# setup a small defaults.parm define AP_PARAM_MAX_EMBEDDED_PARAM 512 # order of UARTs @@ -50,6 +50,7 @@ define DEFAULT_SERIAL0_BAUD 57600 PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD +# activity LED PB14 LED OUTPUT HIGH define HAL_LED_ON 1 @@ -59,36 +60,32 @@ PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW -# --------------------- SPI1 RM3100 ----------------------- +define CAN_APP_NODE_NAME "org.csky.pmu" +define HAL_CAN_POOL_SIZE 6000 + +# SPI1 RM3100 PA5 SPI1_SCK SPI1 PA6 SPI1_MISO SPI1 PA7 SPI1_MOSI SPI1 PA4 SPARE_CS CS +SPIDEV INA23X SPI1 DEVID1 SPARE_CS MODE1 10*MHZ 10*MHZ -define HAL_CAN_POOL_SIZE 6000 - -# enable battery monitor +# enable temperature define AP_TEMPERATURE_SENSOR_ENABLED 1 define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 1 define HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE +# ADC define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE PA3 BATT_TEMP_SENS ADC1 SCALE(1) +# enable battery monitor define HAL_PERIPH_ENABLE_BATTERY define AP_BATTERY_INA239_ENABLED 1 define AP_BATTERY_INA239_SPI_DEVICE "INA23X" define HAL_BATT_MONITOR_DEFAULT 26 -define CAN_APP_NODE_NAME "org.csky.pmu" - -SPIDEV INA23X SPI1 DEVID1 SPARE_CS MODE1 10*MHZ 10*MHZ - -# ADC pins -#define HAL_USE_ADC FALSE - -define AP_BATTERY_SCRIPTING_ENABLED 1 # bootloader embedding / bootloader flashing not available define AP_BOOTLOADER_FLASHING_ENABLED 0 From b725a881f3817b4b460c0d329aab38bbf9992765 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Fri, 15 Nov 2024 11:50:36 +0300 Subject: [PATCH 139/143] Update defaults.parm --- .../hwdef/CSKY-PMU/defaults.parm | 27 ++++++++++++++++++- 1 file changed, 26 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/defaults.parm index 8b137891791fe..d578f1ee90b5f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/defaults.parm @@ -1 +1,26 @@ - +FORMAT_VERSION 0 +CAN_NODE 0 +CAN_BAUDRATE 1000000 +FLASH_BOOTLOADER 0 +DEBUG 0 +BRD_SERIAL_NUM 0 +BATT_MONITOR 26 +BATT_CAPACITY 3300 +BATT_SERIAL_NUM 0 +BATT_MAX_AMPS 204.8 +BATT_SHUNT 0.0002 +BATT_HIDE_MASK 0 +TEMP1_TYPE 5 +TEMP1_BUS 0 +TEMP1_ADDR 0 +TEMP1_SRC 0 +TEMP1_SRC_ID 0 +TEMP1_PIN 3 +TEMP1_A0 -41.0 +TEMP1_A1 50.0 +TEMP1_A2 0.0 +TEMP1_A3 0.0 +TEMP1_A4 0.0 +TEMP1_A5 0.0 +TEMP_MSG_RATE 0 +OPTIONS 0 From 2b3f3e2dc0d2ad2996bdfbfa83185e7b348f9bae Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Fri, 15 Nov 2024 12:12:43 +0300 Subject: [PATCH 140/143] Update hwdef.dat --- libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat index 624bf58e9e6fa..293c05eceaf92 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef.dat @@ -11,7 +11,7 @@ STORAGE_FLASH_PAGE 2 define HAL_STORAGE_SIZE 8192 # board ID for firmware load -APJ_BOARD_ID 1001 +APJ_BOARD_ID 1212 # setup build for a peripheral firmware env AP_PERIPH 1 From 6f20723b630d21115fb28194ecdacdf346d7b1cd Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Fri, 15 Nov 2024 12:12:52 +0300 Subject: [PATCH 141/143] Update hwdef-bl.dat --- libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef-bl.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef-bl.dat index 175b526608249..60b347368f9d7 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef-bl.dat @@ -12,7 +12,7 @@ FLASH_RESERVE_START_KB 0 FLASH_BOOTLOADER_LOAD_KB 64 # board ID for firmware load -APJ_BOARD_ID 1001 +APJ_BOARD_ID 1212 # crystal frequency OSCILLATOR_HZ 8000000 From d0bc97d8437b862b3f8364daae465aaefbec67c6 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Fri, 15 Nov 2024 12:45:05 +0300 Subject: [PATCH 142/143] Update board_types.txt --- Tools/AP_Bootloader/board_types.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/AP_Bootloader/board_types.txt b/Tools/AP_Bootloader/board_types.txt index 16eda3f59e8dc..333319fc57593 100644 --- a/Tools/AP_Bootloader/board_types.txt +++ b/Tools/AP_Bootloader/board_types.txt @@ -299,6 +299,8 @@ AP_HW_FlywooH743Pro 1181 AP_HW_ESP32_PERIPH 1205 AP_HW_ESP32S3_PERIPH 1206 +AP_HW_CSKY-PMU 1212 + AP_HW_MUPilot 1222 AP_HW_CBUnmanned-CM405-FC 1301 From 8906cb34e68fd59f78a469fc15b701e3f233db78 Mon Sep 17 00:00:00 2001 From: Stepan Potapov <163397281+jstc4ll@users.noreply.github.com> Date: Wed, 20 Nov 2024 09:48:33 +0300 Subject: [PATCH 143/143] Delete libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef_old.dat --- .../hwdef/CSKY-PMU/hwdef_old.dat | 85 ------------------- 1 file changed, 85 deletions(-) delete mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef_old.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef_old.dat b/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef_old.dat deleted file mode 100644 index 5bfb065003fe1..0000000000000 --- a/libraries/AP_HAL_ChibiOS/hwdef/CSKY-PMU/hwdef_old.dat +++ /dev/null @@ -1,85 +0,0 @@ -# hw definition file for processing by chibios_pins.py -# MCU class and specific type - -# MCU class and specific type -MCU STM32F4xx STM32F412Rx - -# bootloader starts firmware at 64k -FLASH_RESERVE_START_KB 64 - -# store parameters in pages 2 and 3 -STORAGE_FLASH_PAGE 2 -define HAL_STORAGE_SIZE 8192 - -# board ID for firmware load -APJ_BOARD_ID 1001 - -# setup build for a peripheral firmware -env AP_PERIPH 1 - -STM32_ST_USE_TIMER 5 - -# enable watchdog - -# crystal frequency -OSCILLATOR_HZ 8000000 - -define CH_CFG_ST_FREQUENCY 1000000 - -# assume 512k flash part -FLASH_SIZE_KB 512 - -define HAL_NO_GPIO_IRQ -define SERIAL_BUFFERS_SIZE 512 -define PORT_INT_REQUIRED_STACK 64 - -define DMA_RESERVE_SIZE 0 - -define HAL_NO_MONITOR_THREAD - -# we setup a small defaults.parm -define AP_PARAM_MAX_EMBEDDED_PARAM 512 - -# order of UARTs -SERIAL_ORDER USART1 EMPTY EMPTY EMPTY - -# USART1 for debug -PB6 USART1_TX USART1 NODMA -PB7 USART1_RX USART1 NODMA -define DEFAULT_SERIAL0_BAUD 57600 - -# debugger support -PA13 JTMS-SWDIO SWD -PA14 JTCK-SWCLK SWD - -#CAN bus -CAN_ORDER 1 -PB8 CAN1_RX CAN1 -PB9 CAN1_TX CAN1 -PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW - -define HAL_CAN_POOL_SIZE 6000 - -# BATTERY -define HAL_PERIPH_ENABLE_BATTERY - -define HAL_USE_ADC TRUE -define STM32_ADC_USE_ADC1 TRUE - -PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) -PA2 BATT_CURRENT_SENS ADC1 SCALE(1) -PA3 BATT_TEMP_SENS ADC1 SCALE(1) - -define AP_TEMPERATURE_SENSOR_ENABLED 1 -define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 1 - -define HAL_BATT_MONITOR_DEFAULT 4 -define HAL_BATT_VOLT_PIN 1 -define HAL_BATT_VOLT_SCALE 21.0 -define HAL_BATT_CURR_PIN 2 -define HAL_BATT_CURR_SCALE 40.0 - -define AP_BATTERY_SCRIPTING_ENABLED 1 - -# bootloader embedding / bootloader flashing not available -define AP_BOOTLOADER_FLASHING_ENABLED 0