diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat index 0cd10d5649..e8ea6a5307 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat @@ -21,7 +21,6 @@ env AP_PERIPH 1 STM32_ST_USE_TIMER 5 # enable watchdog -define HAL_WATCHDOG_ENABLED_DEFAULT true # crystal frequency OSCILLATOR_HZ 16000000 @@ -90,7 +89,6 @@ define NO_DATAFLASH TRUE define DMA_RESERVE_SIZE 0 -define PERIPH_FW TRUE define HAL_DISABLE_LOOP_DELAY @@ -101,8 +99,6 @@ PB2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.birdcandy" @@ -112,7 +108,6 @@ define HAL_NO_MONITOR_THREAD define HAL_MINIMIZE_FEATURES 0 -define HAL_BUILD_AP_PERIPH define HAL_DEVICE_THREAD_STACK 768 @@ -133,8 +128,4 @@ define HAL_PERIPH_NEOPIXEL_COUNT 8 define HAL_PERIPH_NEOPIXEL_CHAN 0 define AP_PERIPH_LED_BRIGHT_DEFAULT 50 -# use the app descriptor needed by MissionPlanner for CAN upload -env APP_DESCRIPTOR MissionPlanner -# reserve 256 bytes for comms between app and bootloader -RAM_RESERVE_START 256 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat index f3969df4ec..0d9c5abc59 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat @@ -20,7 +20,6 @@ env AP_PERIPH 1 STM32_ST_USE_TIMER 5 # enable watchdog -define HAL_WATCHDOG_ENABLED_DEFAULT true # crystal frequency OSCILLATOR_HZ 16000000 @@ -117,7 +116,6 @@ define NO_DATAFLASH TRUE define DMA_RESERVE_SIZE 0 -define PERIPH_FW TRUE define HAL_DISABLE_LOOP_DELAY @@ -128,8 +126,6 @@ PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.cuav_gps" @@ -137,7 +133,6 @@ define HAL_NO_MONITOR_THREAD define HAL_MINIMIZE_FEATURES 0 -define HAL_BUILD_AP_PERIPH define HAL_DEVICE_THREAD_STACK 768 @@ -156,8 +151,4 @@ define HAL_PERIPH_ENABLE_BARO define HAL_PERIPH_ENABLE_RC_OUT define HAL_PERIPH_ENABLE_NOTIFY -# use the app descriptor needed by MissionPlanner for CAN upload -env APP_DESCRIPTOR MissionPlanner -# reserve 256 bytes for comms between app and bootloader -RAM_RESERVE_START 256 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef.dat index 10e40cf877..01d7e96dde 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef.dat @@ -22,17 +22,13 @@ APJ_BOARD_ID 1401 # setup build for a peripheral firmware env AP_PERIPH 1 -define PERIPH_FW TRUE -define HAL_BUILD_AP_PERIPH define HAL_PERIPH_ENABLE_GPS define HAL_PERIPH_ENABLE_MAG define HAL_PERIPH_ENABLE_BARO define HAL_PERIPH_ENABLE_RC_OUT -# use the app descriptor needed by MissionPlanner for CAN upload -env APP_DESCRIPTOR MissionPlanner # single GPS and compass for peripherals define GPS_MAX_RECEIVERS 1 @@ -53,12 +49,9 @@ define HAL_BARO_ALLOW_INIT_NO_BARO define HAL_PERIPH_ENABLE_BATTERY -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.CubeBlack-periph" -# reserve 256 bytes for comms between app and bootloader -RAM_RESERVE_START 256 env DISABLE_SCRIPTING 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph-heavy/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph-heavy/hwdef.dat index fd31e6ef83..22849d6ec8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph-heavy/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph-heavy/hwdef.dat @@ -14,9 +14,7 @@ APJ_BOARD_ID 1400 env AP_PERIPH 1 env AP_PERIPH_HEAVY 1 -define PERIPH_FW TRUE -define HAL_BUILD_AP_PERIPH define HAL_PERIPH_ENABLE_BATTERY define HAL_PERIPH_ENABLE_BATTERY_MPPT_PACKETDIGITAL @@ -29,8 +27,6 @@ define COMPASS_CAL_ENABLED 1 define HAL_INS_ENABLED 1 -# use the app descriptor needed by MissionPlanner for CAN upload -env APP_DESCRIPTOR MissionPlanner # single GPS and compass for peripherals define GPS_MAX_RECEIVERS 1 @@ -49,12 +45,9 @@ define HAL_NO_RCIN_THREAD define HAL_BARO_ALLOW_INIT_NO_BARO -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.CubeOrange-periph" -# reserve 256 bytes for comms between app and bootloader -RAM_RESERVE_START 256 env DISABLE_SCRIPTING 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat index e304e3cef4..a071f88c28 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat @@ -13,9 +13,7 @@ APJ_BOARD_ID 1400 # setup build for a peripheral firmware env AP_PERIPH 1 -define PERIPH_FW TRUE -define HAL_BUILD_AP_PERIPH define HAL_PERIPH_ENABLE_BATTERY define HAL_PERIPH_ENABLE_BATTERY_MPPT_PACKETDIGITAL @@ -27,8 +25,6 @@ define HAL_PERIPH_ENABLE_NOTIFY define HAL_INS_ENABLED 1 -# use the app descriptor needed by MissionPlanner for CAN upload -env APP_DESCRIPTOR MissionPlanner # single GPS and compass for peripherals define GPS_MAX_RECEIVERS 1 @@ -47,12 +43,9 @@ define HAL_NO_RCIN_THREAD define HAL_BARO_ALLOW_INIT_NO_BARO -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.CubeOrange-periph" -# reserve 256 bytes for comms between app and bootloader -RAM_RESERVE_START 256 env DISABLE_SCRIPTING 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat index e7548fce8d..24a2c113aa 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat @@ -115,8 +115,6 @@ define HAL_DISABLE_LOOP_DELAY PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.FreeflyRTK" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef.dat index 88cb9c511a..052cbeb253 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef.dat @@ -17,7 +17,6 @@ APJ_BOARD_ID 1027 env AP_PERIPH 1 # enable watchdog -define HAL_WATCHDOG_ENABLED_DEFAULT true # crystal frequency OSCILLATOR_HZ 24000000 @@ -93,7 +92,6 @@ define NO_DATAFLASH TRUE define DMA_RESERVE_SIZE 2048 -define PERIPH_FW TRUE # stack for fast interrupts define PORT_INT_REQUIRED_STACK 64 @@ -141,7 +139,6 @@ define HAL_NO_MONITOR_THREAD define HAL_MINIMIZE_FEATURES 0 -define HAL_BUILD_AP_PERIPH define HAL_DEVICE_THREAD_STACK 0x200 define STORAGE_THD_WA_SIZE 512 @@ -149,18 +146,12 @@ define IO_THD_WA_SIZE 512 define AP_PARAM_MAX_EMBEDDED_PARAM 512 -# use the app descriptor needed by MissionPlanner for CAN upload -env APP_DESCRIPTOR MissionPlanner -# 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 -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.G4-ESC" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef.dat index f8f0752095..65eaeb342e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef.dat @@ -25,7 +25,6 @@ FLASH_SIZE_KB 2048 # setup build for a peripheral firmware # env AP_PERIPH 1 -# define HAL_BUILD_AP_PERIPH # define HAL_GCS_ENABLED 0 # bootloader is installed at zero offset @@ -57,8 +56,6 @@ SERIAL_ORDER USART1 define HAL_USE_EMPTY_STORAGE 1 define HAL_STORAGE_SIZE 16384 -# reserve 256 bytes for comms between app and bootloader -RAM_RESERVE_START 256 # no ADC driver define HAL_USE_ADC FALSE @@ -83,8 +80,6 @@ PF6 QUADSPI_BK1_IO3 QUADSPI1 PG6 QUADSPI_BK1_NCS QUADSPI1 PB2 QUADSPI_CLK QUADSPI1 -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.cubepilot.H757" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL_intf/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL_intf/hwdef.dat index 8c6309e2b6..0af48b153f 100755 --- a/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL_intf/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL_intf/hwdef.dat @@ -25,7 +25,6 @@ FLASH_SIZE_KB 2048 # setup build for a peripheral firmware # env AP_PERIPH 1 -# define HAL_BUILD_AP_PERIPH # define HAL_GCS_ENABLED 0 # bootloader is installed at zero offset @@ -57,8 +56,6 @@ SERIAL_ORDER USART1 define HAL_USE_EMPTY_STORAGE 1 define HAL_STORAGE_SIZE 16384 -# reserve 256 bytes for comms between app and bootloader -RAM_RESERVE_START 256 # no ADC driver define HAL_USE_ADC FALSE @@ -83,8 +80,6 @@ PF6 QUADSPI_BK1_IO3 QUADSPI1 PG6 QUADSPI_BK1_NCS QUADSPI1 PB2 QUADSPI_CLK QUADSPI1 -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.cubepilot.H757" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HereCommon/hwdef-bl.inc b/libraries/AP_HAL_ChibiOS/hwdef/HereCommon/hwdef-bl.inc index f431982350..29101df24f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HereCommon/hwdef-bl.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/HereCommon/hwdef-bl.inc @@ -12,7 +12,6 @@ env AP_PERIPH 1 FLASH_SIZE_KB 2048 -# reserve 256 bytes for comms between app and bootloader # the location where the bootloader will put the firmware # the H743 has 128k sectors diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HereCommon/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/HereCommon/hwdef.inc index 30e93ac4a0..e1f4b4b6b7 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HereCommon/hwdef.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/HereCommon/hwdef.inc @@ -9,13 +9,9 @@ define SMPS_PWR # setup build for a peripheral firmware env AP_PERIPH 1 -define PERIPH_FW TRUE -define HAL_BUILD_AP_PERIPH FLASH_SIZE_KB 2048 -# reserve 256 bytes for comms between app and bootloader -RAM_RESERVE_START 256 # the location where the bootloader will put the firmware # the H743 has 128k sectors @@ -80,5 +76,4 @@ define HAL_USE_ADC FALSE define STM32_ADC_USE_ADC1 FALSE define HAL_DISABLE_ADC_DRIVER TRUE -define HAL_CAN_DEFAULT_NODE_ID 0 define HAL_GCS_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat index 38cd352da9..ab5ae7a84b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat @@ -66,7 +66,6 @@ define HAL_LOGGING_ENABLED TRUE define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_NO_MONITOR_THREAD -define PERIPH_FW TRUE define HAL_DISABLE_LOOP_DELAY define USB_USE_WAIT TRUE @@ -74,7 +73,6 @@ define HAL_USE_USB_MSD TRUE define HAL_MINIMIZE_FEATURES 0 -define HAL_BUILD_AP_PERIPH define HAL_DEVICE_THREAD_STACK 2048 @@ -94,8 +92,6 @@ define HAL_PERIPH_ENABLE_GPS define HAL_PERIPH_ENABLE_MAG define HAL_INS_ENABLED 1 -# use the app descriptor needed by MissionPlanner for CAN upload -env APP_DESCRIPTOR MissionPlanner # enable CAN support PB8 CAN1_RX CAN1 @@ -199,11 +195,7 @@ PH13 VDD_33V_SENS INPUT # This defines some input pins, currently unused. PB2 BOOT1 INPUT -# reserve 256 bytes for comms between app and bootloader -RAM_RESERVE_START 256 -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "com.cubepilot.herepro" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef.dat index 492e0124d4..292d3d8416 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef.dat @@ -17,7 +17,6 @@ APJ_BOARD_ID 1046 env AP_PERIPH 1 # enable watchdog -define HAL_WATCHDOG_ENABLED_DEFAULT true # crystal frequency OSCILLATOR_HZ 24000000 @@ -57,7 +56,6 @@ define NO_DATAFLASH TRUE define DMA_RESERVE_SIZE 512 -define PERIPH_FW TRUE # stack for fast interrupts define PORT_INT_REQUIRED_STACK 64 @@ -92,7 +90,6 @@ define HAL_NO_MONITOR_THREAD define HAL_MINIMIZE_FEATURES 0 -define HAL_BUILD_AP_PERIPH define HAL_DEVICE_THREAD_STACK 0x200 define STORAGE_THD_WA_SIZE 512 @@ -100,18 +97,12 @@ define IO_THD_WA_SIZE 512 define AP_PARAM_MAX_EMBEDDED_PARAM 128 -# use the app descriptor needed by MissionPlanner for CAN upload -env APP_DESCRIPTOR MissionPlanner -# 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 -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.Hitec-Airspeed" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat index 5d9ea40773..f467d1e6c9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat @@ -17,7 +17,6 @@ APJ_BOARD_ID 1016 env AP_PERIPH 1 # enable watchdog -define HAL_WATCHDOG_ENABLED_DEFAULT true # crystal frequency OSCILLATOR_HZ 24000000 @@ -84,7 +83,6 @@ define NO_DATAFLASH TRUE define DMA_RESERVE_SIZE 0 -define PERIPH_FW TRUE # stack for fast interrupts define PORT_INT_REQUIRED_STACK 64 @@ -115,7 +113,6 @@ define HAL_NO_MONITOR_THREAD define HAL_MINIMIZE_FEATURES 0 -define HAL_BUILD_AP_PERIPH # only one I2C bus I2C_ORDER I2C1 @@ -147,18 +144,12 @@ PA6 LED OUTPUT LOW # I2C activity LED PA7 LED_BUS_I2C OUTPUT LOW -# use the app descriptor needed by MissionPlanner for CAN upload -env APP_DESCRIPTOR MissionPlanner -# 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 -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.HitecMosaic" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat index 19ccbd14d1..1dec7d6902 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat @@ -20,7 +20,6 @@ env AP_PERIPH 1 STM32_ST_USE_TIMER 5 # enable watchdog -define HAL_WATCHDOG_ENABLED_DEFAULT true # crystal frequency OSCILLATOR_HZ 16000000 @@ -125,7 +124,6 @@ define NO_DATAFLASH TRUE define DMA_RESERVE_SIZE 0 -define PERIPH_FW TRUE define HAL_DISABLE_LOOP_DELAY @@ -139,8 +137,6 @@ PB12 CAN2_RX CAN2 PB13 CAN2_TX CAN2 PA4 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.HolybroGPS" @@ -149,7 +145,6 @@ define HAL_NO_MONITOR_THREAD define HAL_MINIMIZE_FEATURES 0 -define HAL_BUILD_AP_PERIPH define HAL_DEVICE_THREAD_STACK 768 @@ -174,8 +169,4 @@ define HAL_PERIPH_GPS_PORT_DEFAULT 1 # enable NCP5623 on 2nd I2C bus define BUILD_DEFAULT_LED_TYPE 128 -# use the app descriptor needed by MissionPlanner for CAN upload -env APP_DESCRIPTOR MissionPlanner -# reserve 256 bytes for comms between app and bootloader -RAM_RESERVE_START 256 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat index 95ace1e7f6..69aa76cdfe 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat @@ -14,9 +14,7 @@ APJ_BOARD_ID 1013 # setup build for a peripheral firmware env AP_PERIPH 1 -define PERIPH_FW TRUE -define HAL_BUILD_AP_PERIPH define HAL_PERIPH_ENABLE_GPS define HAL_PERIPH_ENABLE_MAG @@ -27,10 +25,7 @@ define HAL_PERIPH_ENABLE_RANGEFINDER define HAL_PERIPH_ENABLE_RC_OUT define HAL_PERIPH_ENABLE_BATTERY -# use the app descriptor needed by MissionPlanner for CAN upload -env APP_DESCRIPTOR MissionPlanner -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.MatekH743-periph" # single GPS, compass and RF for peripherals @@ -56,8 +51,6 @@ define HAL_USE_RTC FALSE define NO_DATAFLASH TRUE define HAL_NO_RCIN_THREAD -# reserve 256 bytes for comms between app and bootloader -RAM_RESERVE_START 256 env DISABLE_SCRIPTING 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat index 510b2fec66..184499f90c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat @@ -17,7 +17,6 @@ APJ_BOARD_ID 1051 env AP_PERIPH 1 # enable watchdog -define HAL_WATCHDOG_ENABLED_DEFAULT true # crystal frequency OSCILLATOR_HZ 0 @@ -68,7 +67,6 @@ define NO_DATAFLASH TRUE define DMA_RESERVE_SIZE 2048 -define PERIPH_FW TRUE # stack for fast interrupts define PORT_INT_REQUIRED_STACK 64 @@ -96,18 +94,11 @@ define HAL_NO_MONITOR_THREAD define HAL_MINIMIZE_FEATURES 0 -define HAL_BUILD_AP_PERIPH define AP_PARAM_MAX_EMBEDDED_PARAM 512 -# use the app descriptor needed by MissionPlanner for CAN upload -env APP_DESCRIPTOR MissionPlanner -# reserve 256 bytes for comms between app and bootloader -RAM_RESERVE_START 256 -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.Nucleo-L476" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat index e7358761c7..bd156426bc 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat @@ -17,7 +17,6 @@ APJ_BOARD_ID 1047 env AP_PERIPH 1 # enable watchdog -define HAL_WATCHDOG_ENABLED_DEFAULT true # crystal frequency OSCILLATOR_HZ 0 @@ -76,7 +75,6 @@ define NO_DATAFLASH TRUE define DMA_RESERVE_SIZE 2048 -define PERIPH_FW TRUE # stack for fast interrupts define PORT_INT_REQUIRED_STACK 64 @@ -104,18 +102,11 @@ define HAL_NO_MONITOR_THREAD define HAL_MINIMIZE_FEATURES 1 -define HAL_BUILD_AP_PERIPH define AP_PARAM_MAX_EMBEDDED_PARAM 512 -# use the app descriptor needed by MissionPlanner for CAN upload -env APP_DESCRIPTOR MissionPlanner -# reserve 256 bytes for comms between app and bootloader -RAM_RESERVE_START 256 -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.Nucleo-L496" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat index b211be7dec..801a3c6523 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat @@ -25,14 +25,10 @@ APJ_BOARD_ID 1402 # setup build for a peripheral firmware env AP_PERIPH 1 -define PERIPH_FW TRUE -define HAL_BUILD_AP_PERIPH define HAL_SUPPORT_RCOUT_SERIAL 0 -# use the app descriptor needed by MissionPlanner for CAN upload -env APP_DESCRIPTOR MissionPlanner # disable dual GPS and GPS blending to save flash space define GPS_MAX_RECEIVERS 1 @@ -55,12 +51,9 @@ define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE define HAL_DISABLE_ADC_DRIVER FALSE -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.Pixracer_periph" -# reserve 256 bytes for comms between app and bootloader -RAM_RESERVE_START 256 env DISABLE_SCRIPTING 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-L431/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-L431/hwdef.dat index 3f80f8ff05..85f91c0819 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-L431/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-L431/hwdef.dat @@ -21,7 +21,6 @@ APJ_BOARD_ID 1050 env AP_PERIPH 1 # enable watchdog -define HAL_WATCHDOG_ENABLED_DEFAULT true # crystal frequency OSCILLATOR_HZ 16000000 @@ -85,7 +84,6 @@ define NO_DATAFLASH TRUE define DMA_RESERVE_SIZE 2048 -define PERIPH_FW TRUE # stack for fast interrupts define PORT_INT_REQUIRED_STACK 64 @@ -114,18 +112,11 @@ define HAL_NO_MONITOR_THREAD define HAL_NO_LOGGING define HAL_MINIMIZE_FEATURES 0 -define HAL_BUILD_AP_PERIPH define AP_PARAM_MAX_EMBEDDED_PARAM 512 -# use the app descriptor needed by MissionPlanner for CAN upload -env APP_DESCRIPTOR MissionPlanner -# reserve 256 bytes for comms between app and bootloader -RAM_RESERVE_START 256 -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.Sierra-L431" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat index df06248912..ea70ae61f8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat @@ -12,8 +12,6 @@ define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_ZubaxGNSS" # bootloader starts firmware at 34k FLASH_RESERVE_START_KB 34 -# reserve 256 bytes for comms between app and bootloader -RAM_RESERVE_START 256 # store parameters in last 2 pages define STORAGE_FLASH_PAGE 126 @@ -32,8 +30,6 @@ define CH_CFG_ST_FREQUENCY 1000 FLASH_SIZE_KB 256 -# use the app descriptor needed by MissionPlanner for CAN upload -env APP_DESCRIPTOR MissionPlanner # reserve space for params FLASH_RESERVE_END_KB 2 @@ -73,7 +69,6 @@ PB11 USART3_RX USART3 SPEED_HIGH NODMA define HAL_UART_NODMA # enable watchdog -define HAL_WATCHDOG_ENABLED_DEFAULT true # enable CAN support PA11 CAN_RX CAN @@ -118,7 +113,6 @@ define NO_DATAFLASH TRUE define DMA_RESERVE_SIZE 0 -define PERIPH_FW TRUE MAIN_STACK 0x200 PROCESS_STACK 0xA00 define HAL_DISABLE_LOOP_DELAY @@ -134,7 +128,6 @@ define STORAGE_THD_WA_SIZE 512 define HAL_MINIMIZE_FEATURES 0 -define HAL_BUILD_AP_PERIPH define HAL_I2C_CLEAR_ON_TIMEOUT 0 @@ -152,8 +145,6 @@ BARO MS56XX SPI:ms5611 define HAL_BARO_ALLOW_INIT_NO_BARO -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define HAL_NO_MONITOR_THREAD diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef.dat index 223258c87e..322adffe2d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef.dat @@ -5,8 +5,6 @@ include ../f103-periph/hwdef.inc define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_adsb" -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define HAL_AIRSPEED_BUS_DEFAULT 0 define AIRSPEED_MAX_SENSORS 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-Airspeed/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-Airspeed/hwdef.dat index c69e52d65e..1b6a8301c6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-Airspeed/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-Airspeed/hwdef.dat @@ -2,8 +2,6 @@ include ../f103-periph/hwdef.inc define CAN_APP_NODE_NAME "org.ardupilot.f103_airspeed" -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define HAL_AIRSPEED_BUS_DEFAULT 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat index 22af697314..7348b44ce4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat @@ -1,7 +1,5 @@ include ../f103-periph/hwdef.inc -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_gps" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-HWESC/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-HWESC/hwdef.dat index b0efaedc06..e5943d8ea4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-HWESC/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-HWESC/hwdef.dat @@ -1,6 +1,5 @@ include ../f103-periph/hwdef.inc -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_HWESC" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-QiotekPeriph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-QiotekPeriph/hwdef.dat index 07b914fedd..b5010ad49f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-QiotekPeriph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-QiotekPeriph/hwdef.dat @@ -2,8 +2,6 @@ include ../f103-periph/hwdef.inc define CAN_APP_NODE_NAME "org.ardupilot.f103Qiotek_Periph" -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 undef HAL_COMPASS_MAX_SENSORS 1 define HAL_COMPASS_MAX_SENSORS 2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef.dat index fa93126285..104433c6fa 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef.dat @@ -2,8 +2,6 @@ include ../f103-periph/hwdef.inc define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_rangefinder" -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define HAL_AIRSPEED_BUS_DEFAULT 0 define AIRSPEED_MAX_SENSORS 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-Trigger/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-Trigger/hwdef.dat index 0c29eacac8..d8ebe49f46 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-Trigger/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-Trigger/hwdef.dat @@ -5,8 +5,6 @@ include ../f103-periph/hwdef.inc # setup build for a peripheral firmware env AP_PERIPH 1 -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_trigger" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef-bl.inc b/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef-bl.inc index a9ff771d7d..cb5f175aee 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef-bl.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef-bl.inc @@ -83,7 +83,6 @@ define HAL_BOOTLOADER_TIMEOUT 1000 # want to stay in the bootloader PB6 STAY_IN_BOOTLOADER INPUT FLOATING -# reserve 256 bytes for comms between app and bootloader # Add CS pins to ensure they are high in bootloader PB0 MAG_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.inc index 6cfc4dc740..27a09293e3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.inc @@ -17,7 +17,6 @@ APJ_BOARD_ID 1000 env AP_PERIPH 1 # enable watchdog -define HAL_WATCHDOG_ENABLED_DEFAULT true # crystal frequency OSCILLATOR_HZ 8000000 @@ -76,7 +75,6 @@ define NO_DATAFLASH TRUE define DMA_RESERVE_SIZE 0 -define PERIPH_FW TRUE # MAIN_STACK is stack of initial thread and ISRs MAIN_STACK 0x200 @@ -108,7 +106,6 @@ define HAL_NO_MONITOR_THREAD define HAL_MINIMIZE_FEATURES 0 -define HAL_BUILD_AP_PERIPH # only one I2C bus I2C_ORDER I2C1 @@ -127,11 +124,7 @@ define GPS_MAX_INSTANCES 1 define HAL_COMPASS_MAX_SENSORS 1 define HAL_WITH_DSP FALSE -# use the app descriptor needed by MissionPlanner for CAN upload -env APP_DESCRIPTOR MissionPlanner -# 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 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef.dat index 1eb97534da..bfe5edf0a4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef.dat @@ -1,7 +1,5 @@ include ../f303-periph/hwdef.inc -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_gps" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-HWESC/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-HWESC/hwdef.dat index fcc26b2187..43a756f5e1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-HWESC/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-HWESC/hwdef.dat @@ -1,6 +1,5 @@ include ../f303-periph/hwdef.inc -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_HWESC" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef.dat index 8f79d70cfe..667514ecea 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef.dat @@ -1,7 +1,6 @@ include ../f303-periph/hwdef.inc # start as DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.mro_m10025" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef.dat index 390280f26f..8e9236ca7d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef.dat @@ -4,7 +4,6 @@ include ../f303-periph/hwdef.inc # M10070B # start as DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "io.mrobotics.m10070_loc1" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat index 4828782b84..32aa0488ce 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat @@ -17,7 +17,6 @@ APJ_BOARD_ID 1004 env AP_PERIPH 1 # enable watchdog -define HAL_WATCHDOG_ENABLED_DEFAULT true # crystal frequency OSCILLATOR_HZ 8000000 @@ -55,7 +54,6 @@ define NO_DATAFLASH TRUE define DMA_RESERVE_SIZE 0 -define PERIPH_FW TRUE # MAIN_STACK is stack of initial thread MAIN_STACK 0x300 @@ -83,7 +81,6 @@ define IO_THD_WA_SIZE 512 define HAL_MINIMIZE_FEATURES 0 -define HAL_BUILD_AP_PERIPH # only one I2C bus I2C_ORDER I2C1 @@ -101,11 +98,7 @@ define GPS_MAX_RECEIVERS 1 define GPS_MAX_INSTANCES 1 define HAL_COMPASS_MAX_SENSORS 1 -# use the app descriptor needed by MissionPlanner for CAN upload -env APP_DESCRIPTOR MissionPlanner -# 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 @@ -127,7 +120,6 @@ PB10 USART3_TX USART3 SPEED_HIGH PB11 USART3_RX USART3 SPEED_HIGH # use DNA for node allocation -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.f303_MatekGPS" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-PWM/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-PWM/hwdef.dat index faad20c471..898d0715e8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-PWM/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-PWM/hwdef.dat @@ -1,7 +1,5 @@ include ../f303-periph/hwdef.inc -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_PWM" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat index ef6b0b9579..507a90719f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat @@ -1,7 +1,5 @@ include ../f303-periph/hwdef.inc -# use DNA -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_universal" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef-bl.inc b/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef-bl.inc index 106a6bbb83..09da6d4213 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef-bl.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef-bl.inc @@ -83,7 +83,6 @@ define HAL_BOOTLOADER_TIMEOUT 1000 # want to stay in the bootloader PB6 STAY_IN_BOOTLOADER INPUT FLOATING -# reserve 256 bytes for comms between app and bootloader # Add CS pins to ensure they are high in bootloader PB0 MAG_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.inc index 87581dbef1..1f454089aa 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.inc @@ -17,7 +17,6 @@ APJ_BOARD_ID 1004 env AP_PERIPH 1 # enable watchdog -define HAL_WATCHDOG_ENABLED_DEFAULT true # crystal frequency OSCILLATOR_HZ 8000000 @@ -76,7 +75,6 @@ define NO_DATAFLASH TRUE define DMA_RESERVE_SIZE 0 -define PERIPH_FW TRUE # MAIN_STACK is stack of initial thread and of ISRs MAIN_STACK 0x300 @@ -124,8 +122,6 @@ define GPS_MAX_INSTANCES 1 define HAL_COMPASS_MAX_SENSORS 1 define RANGEFINDER_MAX_INSTANCES 1 -# 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 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat index 6cec912823..e631f40957 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat @@ -15,14 +15,11 @@ define HAL_STORAGE_SIZE 15360 APJ_BOARD_ID 1014 env AP_PERIPH 1 -define PERIPH_FW TRUE -define HAL_BUILD_AP_PERIPH define STM32_ST_USE_TIMER 5 define CH_CFG_ST_RESOLUTION 32 # enable watchdog -define HAL_WATCHDOG_ENABLED_DEFAULT true # crystal frequency OSCILLATOR_HZ 8000000 @@ -58,11 +55,7 @@ define HAL_DEVICE_THREAD_STACK 768 # we setup a small defaults.parm define AP_PARAM_MAX_EMBEDDED_PARAM 256 -# use the app descriptor needed by MissionPlanner for CAN upload -env APP_DESCRIPTOR MissionPlanner -# 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 @@ -109,7 +102,6 @@ PB9 CAN1_TX CAN1 PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW # use DNA for node allocation -define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.f405_MatekGPS" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/mRo-M10095/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/mRo-M10095/hwdef.dat index c40cfe6ad5..2ce32bd3fd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/mRo-M10095/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/mRo-M10095/hwdef.dat @@ -62,8 +62,6 @@ define NO_DATAFLASH TRUE define DMA_RESERVE_SIZE 2048 -define PERIPH_FW TRUE - define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE @@ -90,16 +88,8 @@ define HAL_NO_MONITOR_THREAD define HAL_MINIMIZE_FEATURES 0 -define HAL_BUILD_AP_PERIPH - define AP_PARAM_MAX_EMBEDDED_PARAM 512 -# use the app descriptor needed by MissionPlanner for CAN upload -env APP_DESCRIPTOR MissionPlanner - -# 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