From 6b3bdef6fd4201fd46bc818777a8184bcd1d3831 Mon Sep 17 00:00:00 2001 From: "Git bot (blckmn)" Date: Fri, 30 May 2025 06:25:03 +0000 Subject: [PATCH 1/8] Auto updated submodule references [30-05-2025] --- src/config | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/config b/src/config index 4136fa21f2..0ce3bf0f2c 160000 --- a/src/config +++ b/src/config @@ -1 +1 @@ -Subproject commit 4136fa21f2902321caad438b73505caf0c64dda3 +Subproject commit 0ce3bf0f2c3749e93866a640f2af3fd6754db824 From 31e5644b560b09f19f9afe8e9e710f41604aa9f0 Mon Sep 17 00:00:00 2001 From: Petr Ledvina Date: Fri, 30 May 2025 18:54:54 +0200 Subject: [PATCH 2/8] rangefinderTF refactor + add TF-Nova (#14379) * Add rangefinder TF-Nova * fix * Return comments. Removed spaces * Removed invalid command. Expanded range * tfmini and tf02 united command for 100hz sampling * add aray and enum * add array and enum * RANGEFINDER - reafactor lidartf - use info array - rename some functions - init as for lidarMT - config lidar on initialization (functional change) * RANGEFINDER - common TF detection using rangefinderTYpe * prevent too frequent lidar reconf suggested by @coderabbitai * trace errors in debug * fix tfFrame length @coderabbitai * update public header @coderabbitai * Fix problems from upstream merge * RAngefinder - minor cleanup --------- Co-authored-by: LarryKarhu --- .../drivers/rangefinder/rangefinder_lidartf.c | 235 +++++++++--------- .../drivers/rangefinder/rangefinder_lidartf.h | 9 +- src/main/sensors/rangefinder.c | 24 +- 3 files changed, 120 insertions(+), 148 deletions(-) diff --git a/src/main/drivers/rangefinder/rangefinder_lidartf.c b/src/main/drivers/rangefinder/rangefinder_lidartf.c index 643b66694a..51e4043fa4 100644 --- a/src/main/drivers/rangefinder/rangefinder_lidartf.c +++ b/src/main/drivers/rangefinder/rangefinder_lidartf.c @@ -34,16 +34,24 @@ #include "drivers/rangefinder/rangefinder.h" #include "drivers/rangefinder/rangefinder_lidartf.h" -#define TF_DEVTYPE_NONE 0 -#define TF_DEVTYPE_MINI 1 -#define TF_DEVTYPE_02 2 -#define TF_DEVTYPE_NOVA 3 +typedef struct { + rangefinderType_e rfType; + uint16_t rangeMin; + uint16_t rangeMax; +} lidarTFInfo_t; -static uint8_t tfDevtype = TF_DEVTYPE_NONE; + +static const lidarTFInfo_t *devInfo = NULL; +static const lidarTFInfo_t devInfos[] = { + { .rfType = RANGEFINDER_TFMINI, .rangeMin = 40, .rangeMax = 1200}, + { .rfType = RANGEFINDER_TF02, .rangeMin = 40, .rangeMax = 2200}, + { .rfType = RANGEFINDER_TFNOVA, .rangeMin = 10, .rangeMax = 1400}, +}; #define TF_FRAME_LENGTH 6 // Excluding sync bytes (0x59) x 2 and checksum #define TF_FRAME_SYNC_BYTE 0x59 #define TF_TIMEOUT_MS (100 * 2) +#define TF_TASK_PERIOD_MS 10 // // Benewake TFmini frame format @@ -98,21 +106,10 @@ static uint8_t tfDevtype = TF_DEVTYPE_NONE; // Credibility // 1. If Confidence level < 90, unreliable // 2. If distance is 14m (1400cm), then OoR. -// + #define TF_NOVA_FRAME_CONFIDENCE 5 -// Maximum ratings - -#define TF_MINI_RANGE_MIN 40 -#define TF_MINI_RANGE_MAX 1200 - -#define TF_02_RANGE_MIN 40 -#define TF_02_RANGE_MAX 2200 - -#define TF_NOVA_RANGE_MIN 10 -#define TF_NOVA_RANGE_MAX 1400 - -#define TF_DETECTION_CONE_DECIDEGREES 900 +#define TF_DETECTION_CONE_DECIDEGREES 900 // TODO static serialPort_t *tfSerialPort = NULL; @@ -130,21 +127,35 @@ static uint8_t tfReceivePosition; // TFmini and TF02 // Command for 100Hz sampling (10msec interval) // At 100Hz scheduling, skew will cause 10msec delay at the most. -static const uint8_t tfCmd[] = { 0x42, 0x57, 0x02, 0x00, 0x00, 0x00, 0x01, 0x06 }; +// This command format does not match latest Benewake documentation +static const uint8_t tfConfigCmd[] = { 0x42, 0x57, 0x02, 0x00, 0x00, 0x00, 0x01, 0x06 }; -static int32_t lidarTFValue; -static uint16_t lidarTFerrors = 0; +static int lidarTFValue; +static unsigned lidarTFerrors = 0; -static void lidarTFSendCommand(void) + +static const lidarTFInfo_t* findInfo(rangefinderType_e rfType) { - switch (tfDevtype) { - case TF_DEVTYPE_MINI: - case TF_DEVTYPE_02: - serialWriteBuf(tfSerialPort, tfCmd, sizeof(tfCmd)); + for (const lidarTFInfo_t* p = devInfos; p < ARRAYEND(devInfos); p++) { + if (p->rfType == rfType) { + return p; + } + } + return NULL; +} + +// configure/reconfigure device +// may be called multiple times (when frames are missing) +static void lidarTFConfig(rangefinderDev_t *dev, const lidarTFInfo_t* inf) +{ + UNUSED(dev); + switch (inf->rfType) { + case RANGEFINDER_TFMINI: + case RANGEFINDER_TF02: + serialWriteBuf(tfSerialPort, tfConfigCmd, sizeof(tfConfigCmd)); break; default: break; - } } @@ -156,13 +167,54 @@ static void lidarTFInit(rangefinderDev_t *dev) tfReceivePosition = 0; } +static int tfProcessFrame(const uint8_t* frame, int len) +{ + UNUSED(len); + uint16_t distance = frame[0] | (frame[1] << 8); + uint16_t strength = frame[2] | (frame[3] << 8); + + DEBUG_SET(DEBUG_LIDAR_TF, 0, distance); // 0,1 + DEBUG_SET(DEBUG_LIDAR_TF, 1, strength); // 2,3 + DEBUG_SET(DEBUG_LIDAR_TF, 2, frame[4]); + DEBUG_SET(DEBUG_LIDAR_TF, 3, frame[5]); + + // common distance check + if (distance < devInfo->rangeMin || distance > devInfo->rangeMax) { + return RANGEFINDER_OUT_OF_RANGE; + } + + switch (devInfo->rfType) { + case RANGEFINDER_TFMINI: + if (frame[TF_MINI_FRAME_INTEGRAL_TIME] == 7) { + // When integral time is long (7), measured distance tends to be longer by 12~13. + distance -= 13; + } + break; + case RANGEFINDER_TF02: + if (frame[TF_02_FRAME_SIG] < 7) { + return RANGEFINDER_OUT_OF_RANGE; + + } + break; + case RANGEFINDER_TFNOVA: + if (frame[TF_NOVA_FRAME_CONFIDENCE] < 90) { + return RANGEFINDER_OUT_OF_RANGE; + } + break; + default: + return RANGEFINDER_HARDWARE_FAILURE; // internal error + } + // distance is valid + return distance; +} + static void lidarTFUpdate(rangefinderDev_t *dev) { - UNUSED(dev); static timeMs_t lastFrameReceivedMs = 0; + static timeMs_t lastReconfMs = 0; const timeMs_t timeNowMs = millis(); - if (tfSerialPort == NULL) { + if (tfSerialPort == NULL || devInfo == NULL) { return; } @@ -190,76 +242,37 @@ static void lidarTFUpdate(rangefinderDev_t *dev) } break; - case TF_FRAME_STATE_WAIT_CKSUM: - { - uint8_t cksum = TF_FRAME_SYNC_BYTE + TF_FRAME_SYNC_BYTE; - for (int i = 0; i < TF_FRAME_LENGTH; i++) { - cksum += tfFrame[i]; - } - - if (c == cksum) { - - uint16_t distance = tfFrame[0] | (tfFrame[1] << 8); - uint16_t strength = tfFrame[2] | (tfFrame[3] << 8); - - DEBUG_SET(DEBUG_LIDAR_TF, 0, distance); - DEBUG_SET(DEBUG_LIDAR_TF, 1, strength); - DEBUG_SET(DEBUG_LIDAR_TF, 2, tfFrame[4]); - DEBUG_SET(DEBUG_LIDAR_TF, 3, tfFrame[5]); - - switch (tfDevtype) { - case TF_DEVTYPE_MINI: - if (distance >= TF_MINI_RANGE_MIN && distance < TF_MINI_RANGE_MAX) { - lidarTFValue = distance; - if (tfFrame[TF_MINI_FRAME_INTEGRAL_TIME] == 7) { - // When integral time is long (7), measured distance tends to be longer by 12~13. - lidarTFValue -= 13; - } - } else { - lidarTFValue = -1; - } - break; - - case TF_DEVTYPE_02: - if (distance >= TF_02_RANGE_MIN && distance < TF_02_RANGE_MAX && tfFrame[TF_02_FRAME_SIG] >= 7) { - lidarTFValue = distance; - } else { - lidarTFValue = -1; - } - break; - - case TF_DEVTYPE_NOVA: - if (distance >= TF_NOVA_RANGE_MIN && distance <= TF_NOVA_RANGE_MAX && tfFrame[TF_NOVA_FRAME_CONFIDENCE] >= 90) { - lidarTFValue = distance; - } else { - lidarTFValue = -1; - } - break; - } - lastFrameReceivedMs = timeNowMs; - } else { - // Checksum error. Simply discard the current frame. - ++lidarTFerrors; - //DEBUG_SET(DEBUG_LIDAR_TF, 3, lidarTFerrors); - } + case TF_FRAME_STATE_WAIT_CKSUM: { + uint8_t cksum = TF_FRAME_SYNC_BYTE + TF_FRAME_SYNC_BYTE; // SYNC bytes are checksummed too, but not stored + for (int i = 0; i < TF_FRAME_LENGTH; i++) { + cksum += tfFrame[i]; } + if (c == cksum) { + lidarTFValue = tfProcessFrame(tfFrame, TF_FRAME_LENGTH); + lastFrameReceivedMs = timeNowMs; + } else { + // Checksum error. Simply ignore the current frame. + ++lidarTFerrors; + DEBUG_SET(DEBUG_LIDAR_TF, 4, lidarTFerrors); + } tfFrameState = TF_FRAME_STATE_WAIT_START1; tfReceivePosition = 0; - break; } + } } - // If valid frame hasn't been received for more than a timeout, resend command. - - if (timeNowMs - lastFrameReceivedMs > TF_TIMEOUT_MS) { - lidarTFSendCommand(); + // If valid frame hasn't been received for more than a timeout, try reinit. + if (cmp32(timeNowMs, lastFrameReceivedMs) > TF_TIMEOUT_MS + && cmp32(timeNowMs, lastReconfMs) > 500) { + lidarTFConfig(dev, devInfo); + lastReconfMs = timeNowMs; // delay sensor reconf } } // Return most recent device output in cm - +// TODO - handle timeout; return value only once (see lidarMT) static int32_t lidarTFGetDistance(rangefinderDev_t *dev) { UNUSED(dev); @@ -267,37 +280,25 @@ static int32_t lidarTFGetDistance(rangefinderDev_t *dev) return lidarTFValue; } -static bool lidarTFDetect(rangefinderDev_t *dev, uint8_t devtype) +bool lidarTFDetect(rangefinderDev_t *dev, rangefinderType_e rfType) { - const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_LIDAR_TF); + const lidarTFInfo_t* inf = findInfo(rfType); + if (!inf) { + return false; // supplied rfType is not TF + } + const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_LIDAR_TF); if (!portConfig) { return false; } tfSerialPort = openSerialPort(portConfig->identifier, FUNCTION_LIDAR_TF, NULL, NULL, 115200, MODE_RXTX, 0); - if (tfSerialPort == NULL) { return false; } - tfDevtype = devtype; - - dev->delayMs = 10; - switch (devtype) { - case TF_DEVTYPE_MINI: - dev->maxRangeCm = TF_MINI_RANGE_MAX; - break; - case TF_DEVTYPE_02: - dev->maxRangeCm = TF_02_RANGE_MAX; - break; - case TF_DEVTYPE_NOVA: - dev->maxRangeCm = TF_NOVA_RANGE_MAX; - break; - default: - dev->maxRangeCm = 0; - break; - } + dev->delayMs = TF_TASK_PERIOD_MS; + dev->maxRangeCm = inf->rangeMax; dev->detectionConeDeciDegrees = TF_DETECTION_CONE_DECIDEGREES; dev->detectionConeExtendedDeciDegrees = TF_DETECTION_CONE_DECIDEGREES; @@ -306,22 +307,12 @@ static bool lidarTFDetect(rangefinderDev_t *dev, uint8_t devtype) dev->update = &lidarTFUpdate; dev->read = &lidarTFGetDistance; + devInfo = inf; + + // configure device + lidarTFConfig(dev, devInfo); + return true; } -bool lidarTFminiDetect(rangefinderDev_t *dev) -{ - return lidarTFDetect(dev, TF_DEVTYPE_MINI); -} - -bool lidarTF02Detect(rangefinderDev_t *dev) -{ - return lidarTFDetect(dev, TF_DEVTYPE_02); -} - -bool lidarTFNovaDetect(rangefinderDev_t *dev) -{ - return lidarTFDetect(dev, TF_DEVTYPE_NOVA); -} - #endif diff --git a/src/main/drivers/rangefinder/rangefinder_lidartf.h b/src/main/drivers/rangefinder/rangefinder_lidartf.h index cd786a79bc..c84370dd4c 100644 --- a/src/main/drivers/rangefinder/rangefinder_lidartf.h +++ b/src/main/drivers/rangefinder/rangefinder_lidartf.h @@ -20,10 +20,7 @@ #pragma once -#include "common/time.h" +#include "drivers/rangefinder/rangefinder.h" +#include "sensors/rangefinder.h" -#define RANGEFINDER_TF_TASK_PERIOD_MS 10 - -bool lidarTFminiDetect(rangefinderDev_t *dev); -bool lidarTF02Detect(rangefinderDev_t *dev); -bool lidarTFNovaDetect(rangefinderDev_t *dev); +bool lidarTFDetect(rangefinderDev_t *dev, rangefinderType_e rfType); diff --git a/src/main/sensors/rangefinder.c b/src/main/sensors/rangefinder.c index e243b5027f..4c1ac78d69 100644 --- a/src/main/sensors/rangefinder.c +++ b/src/main/sensors/rangefinder.c @@ -109,29 +109,13 @@ static bool rangefinderDetect(rangefinderDev_t * dev, uint8_t rangefinderHardwar #endif break; +#if defined(USE_RANGEFINDER_TF) case RANGEFINDER_TFMINI: -#if defined(USE_RANGEFINDER_TF) - if (lidarTFminiDetect(dev)) { - rangefinderHardware = RANGEFINDER_TFMINI; - rescheduleTask(TASK_RANGEFINDER, TASK_PERIOD_MS(RANGEFINDER_TF_TASK_PERIOD_MS)); - } -#endif - break; - case RANGEFINDER_TF02: -#if defined(USE_RANGEFINDER_TF) - if (lidarTF02Detect(dev)) { - rangefinderHardware = RANGEFINDER_TF02; - rescheduleTask(TASK_RANGEFINDER, TASK_PERIOD_MS(RANGEFINDER_TF_TASK_PERIOD_MS)); - } -#endif - break; - case RANGEFINDER_TFNOVA: -#if defined(USE_RANGEFINDER_TF) - if (lidarTFNovaDetect(dev)) { - rangefinderHardware = RANGEFINDER_TFNOVA; - rescheduleTask(TASK_RANGEFINDER, TASK_PERIOD_MS(RANGEFINDER_TF_TASK_PERIOD_MS)); + if (lidarTFDetect(dev, rangefinderHardwareToUse)) { + rangefinderHardware = rangefinderHardwareToUse; + rescheduleTask(TASK_RANGEFINDER, TASK_PERIOD_MS(dev->delayMs)); } #endif break; From 2d81c87927ee8cb7719c04a2d5adebd0e338e74e Mon Sep 17 00:00:00 2001 From: Mark Haslinghuis Date: Fri, 30 May 2025 21:47:07 +0200 Subject: [PATCH 3/8] Improve 426xx detection time using soft reset (#14414) * Improve 426xx detection using softreset * Update src/main/drivers/accgyro/accgyro_spi_icm426xx.c Co-authored-by: Petr Ledvina * Update src/main/drivers/accgyro/accgyro_spi_icm426xx.c Co-authored-by: Petr Ledvina --------- Co-authored-by: Petr Ledvina --- src/main/drivers/accgyro/accgyro_spi_icm426xx.c | 17 ++++++++++++++++- 1 file changed, 16 insertions(+), 1 deletion(-) diff --git a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c index 2a3a327e4d..b323d2211d 100644 --- a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c +++ b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c @@ -60,6 +60,10 @@ #define ICM426XX_CLKIN_FREQ 32000 +// Soft Reset +#define ICM426XX_RA_DEVICE_CONFIG 0x17 +#define DEVICE_CONFIG_SOFT_RESET_BIT (1 << 0) // Soft reset bit + #define ICM426XX_RA_REG_BANK_SEL 0x76 #define ICM426XX_BANK_SELECT0 0x00 #define ICM426XX_BANK_SELECT1 0x01 @@ -249,8 +253,19 @@ static void icm426xxEnableExternalClock(const extDevice_t *dev) } #endif +static void icm426xxSoftReset(const extDevice_t *dev) +{ + setUserBank(dev, ICM426XX_BANK_SELECT0); + + spiWriteReg(dev, ICM426XX_RA_DEVICE_CONFIG, DEVICE_CONFIG_SOFT_RESET_BIT); + + delay(1); +} + uint8_t icm426xxSpiDetect(const extDevice_t *dev) { + delay(1); // power-on time + icm426xxSoftReset(dev); spiWriteReg(dev, ICM426XX_RA_PWR_MGMT0, 0x00); #if defined(USE_GYRO_CLKIN) @@ -260,7 +275,7 @@ uint8_t icm426xxSpiDetect(const extDevice_t *dev) uint8_t icmDetected = MPU_NONE; uint8_t attemptsRemaining = 20; do { - delay(150); + delay(1); const uint8_t whoAmI = spiReadRegMsk(dev, MPU_RA_WHO_AM_I); switch (whoAmI) { case ICM42605_WHO_AM_I_CONST: From 62dd5f6e4cb0b1db8bc921eec2bbccbc50e9ad83 Mon Sep 17 00:00:00 2001 From: Steve Evans Date: Fri, 30 May 2025 20:55:04 +0100 Subject: [PATCH 4/8] Add missing OCTOX8P definition (#14418) --- src/main/cli/cli.c | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/main/cli/cli.c b/src/main/cli/cli.c index 8fd7d3aee2..e12cae2ae6 100644 --- a/src/main/cli/cli.c +++ b/src/main/cli/cli.c @@ -224,7 +224,8 @@ static const char * const mixerNames[] = { "FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX", "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4", "HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER", - "ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", "QUADX1234", NULL + "ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", "QUADX1234", + "OCTOX8P", NULL }; #endif @@ -5000,9 +5001,9 @@ static void cliRcSmoothing(const char *cmdName, char *cmdline) if (rcSmoothingAutoCalculate()) { cliPrint("# Detected Rx frequency: "); if (getRxRateValid()) { - cliPrintLinef("%dHz", lrintf(rcSmoothingData->smoothedRxRateHz)); + cliPrintLinef("%dHz", lrintf(rcSmoothingData->smoothedRxRateHz)); } else { - cliPrintLine("NO SIGNAL"); + cliPrintLine("NO SIGNAL"); } } cliPrintf("# Active setpoint cutoff: %dhz ", rcSmoothingData->setpointCutoffFrequency); From 98582c0c1894eaa1161e2385f13e9e540f43d402 Mon Sep 17 00:00:00 2001 From: Jay Blackman Date: Sat, 31 May 2025 13:35:39 +1000 Subject: [PATCH 5/8] Removing PICO directory, to be reinstated from RP2350 branch (#14413) --- src/main/drivers/io_def.h | 2 +- src/platform/PICO/link/pico_rp2350.ld | 302 ------------------ src/platform/PICO/mk/PICO.mk | 158 --------- src/platform/PICO/platform_mcu.h | 67 ---- .../startup/bs2_default_padded_checksummed.S | 25 -- src/platform/PICO/target/RP2350/.exclude | 0 src/platform/PICO/target/RP2350/target.h | 69 ---- src/platform/PICO/target/RP2350/target.mk | 2 - 8 files changed, 1 insertion(+), 624 deletions(-) delete mode 100644 src/platform/PICO/link/pico_rp2350.ld delete mode 100644 src/platform/PICO/mk/PICO.mk delete mode 100644 src/platform/PICO/platform_mcu.h delete mode 100644 src/platform/PICO/startup/bs2_default_padded_checksummed.S delete mode 100644 src/platform/PICO/target/RP2350/.exclude delete mode 100644 src/platform/PICO/target/RP2350/target.h delete mode 100644 src/platform/PICO/target/RP2350/target.mk diff --git a/src/main/drivers/io_def.h b/src/main/drivers/io_def.h index 8906c71b2a..2204005221 100644 --- a/src/main/drivers/io_def.h +++ b/src/main/drivers/io_def.h @@ -43,7 +43,7 @@ // split ioTag bits between pin and port // port is encoded as +1 to avoid collision with 0x0 (false as bool) -#ifndef DEFIO_PORT_PINS +#ifndef DEFIO_PORT_PINS // pins per port #define DEFIO_PORT_PINS 16 #endif diff --git a/src/platform/PICO/link/pico_rp2350.ld b/src/platform/PICO/link/pico_rp2350.ld deleted file mode 100644 index c8f3dd7c79..0000000000 --- a/src/platform/PICO/link/pico_rp2350.ld +++ /dev/null @@ -1,302 +0,0 @@ -/* Based on GCC ARM embedded samples. - Defines the following symbols for use by code: - __exidx_start - __exidx_end - __etext - __data_start__ - __preinit_array_start - __preinit_array_end - __init_array_start - __init_array_end - __fini_array_start - __fini_array_end - __data_end__ - __bss_start__ - __bss_end__ - __end__ - end - __HeapLimit - __StackLimit - __StackTop - __stack (== StackTop) -*/ - -MEMORY -{ - FLASH(rx) : ORIGIN = 0x10000000, LENGTH = 4m - RAM(rwx) : ORIGIN = 0x20000000, LENGTH = 512k - SCRATCH_X(rwx) : ORIGIN = 0x20080000, LENGTH = 4k - SCRATCH_Y(rwx) : ORIGIN = 0x20081000, LENGTH = 4k -} - -ENTRY(_entry_point) - -SECTIONS -{ - .flash_begin : { - __flash_binary_start = .; - } > FLASH - - /* The bootrom will enter the image at the point indicated in your - IMAGE_DEF, which is usually the reset handler of your vector table. - - The debugger will use the ELF entry point, which is the _entry_point - symbol, and in our case is *different from the bootrom's entry point.* - This is used to go back through the bootrom on debugger launches only, - to perform the same initial flash setup that would be performed on a - cold boot. - */ - - .text : { - __logical_binary_start = .; - KEEP (*(.vectors)) - KEEP (*(.binary_info_header)) - __binary_info_header_end = .; - KEEP (*(.embedded_block)) - __embedded_block_end = .; - KEEP (*(.reset)) - /* TODO revisit this now memset/memcpy/float in ROM */ - /* bit of a hack right now to exclude all floating point and time critical (e.g. memset, memcpy) code from - * FLASH ... we will include any thing excluded here in .data below by default */ - *(.init) - *libgcc.a:cmse_nonsecure_call.o - *(EXCLUDE_FILE(*libgcc.a: *libc.a:*lib_a-mem*.o *libm.a:) .text*) - *(.fini) - /* Pull all c'tors into .text */ - *crtbegin.o(.ctors) - *crtbegin?.o(.ctors) - *(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors) - *(SORT(.ctors.*)) - *(.ctors) - /* Followed by destructors */ - *crtbegin.o(.dtors) - *crtbegin?.o(.dtors) - *(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors) - *(SORT(.dtors.*)) - *(.dtors) - - . = ALIGN(4); - /* preinit data */ - PROVIDE_HIDDEN (__preinit_array_start = .); - KEEP(*(SORT(.preinit_array.*))) - KEEP(*(.preinit_array)) - PROVIDE_HIDDEN (__preinit_array_end = .); - - . = ALIGN(4); - /* init data */ - PROVIDE_HIDDEN (__init_array_start = .); - KEEP(*(SORT(.init_array.*))) - KEEP(*(.init_array)) - PROVIDE_HIDDEN (__init_array_end = .); - - . = ALIGN(4); - /* finit data */ - PROVIDE_HIDDEN (__fini_array_start = .); - *(SORT(.fini_array.*)) - *(.fini_array) - PROVIDE_HIDDEN (__fini_array_end = .); - - *(.eh_frame*) - . = ALIGN(4); - } > FLASH - - /* Note the boot2 section is optional, and should be discarded if there is - no reference to it *inside* the binary, as it is not called by the - bootrom. (The bootrom performs a simple best-effort XIP setup and - leaves it to the binary to do anything more sophisticated.) However - there is still a size limit of 256 bytes, to ensure the boot2 can be - stored in boot RAM. - - Really this is a "XIP setup function" -- the name boot2 is historic and - refers to its dual-purpose on RP2040, where it also handled vectoring - from the bootrom into the user image. - */ - - .boot2 : { - __boot2_start__ = .; - *(.boot2) - __boot2_end__ = .; - } > FLASH - - ASSERT(__boot2_end__ - __boot2_start__ <= 256, - "ERROR: Pico second stage bootloader must be no more than 256 bytes in size") - - .rodata : { - *(EXCLUDE_FILE(*libgcc.a: *libc.a:*lib_a-mem*.o *libm.a:) .rodata*) - *(.srodata*) - . = ALIGN(4); - *(SORT_BY_ALIGNMENT(SORT_BY_NAME(.flashdata*))) - . = ALIGN(4); - } > FLASH - - .ARM.extab : - { - *(.ARM.extab* .gnu.linkonce.armextab.*) - } > FLASH - - __exidx_start = .; - .ARM.exidx : - { - *(.ARM.exidx* .gnu.linkonce.armexidx.*) - } > FLASH - __exidx_end = .; - - /* Machine inspectable binary information */ - . = ALIGN(4); - __binary_info_start = .; - .binary_info : - { - KEEP(*(.binary_info.keep.*)) - *(.binary_info.*) - } > FLASH - __binary_info_end = .; - . = ALIGN(4); - - .ram_vector_table (NOLOAD): { - *(.ram_vector_table) - } > RAM - - .uninitialized_data (NOLOAD): { - . = ALIGN(4); - *(.uninitialized_data*) - } > RAM - - .data : { - __data_start__ = .; - *(vtable) - - *(.time_critical*) - - /* remaining .text and .rodata; i.e. stuff we exclude above because we want it in RAM */ - *(.text*) - . = ALIGN(4); - *(.rodata*) - . = ALIGN(4); - - *(.data*) - *(.sdata*) - - . = ALIGN(4); - *(.after_data.*) - . = ALIGN(4); - /* preinit data */ - PROVIDE_HIDDEN (__mutex_array_start = .); - KEEP(*(SORT(.mutex_array.*))) - KEEP(*(.mutex_array)) - PROVIDE_HIDDEN (__mutex_array_end = .); - - *(.jcr) - . = ALIGN(4); - } > RAM AT> FLASH - - .tdata : { - . = ALIGN(4); - *(.tdata .tdata.* .gnu.linkonce.td.*) - /* All data end */ - __tdata_end = .; - } > RAM AT> FLASH - PROVIDE(__data_end__ = .); - - /* __etext is (for backwards compatibility) the name of the .data init source pointer (...) */ - __etext = LOADADDR(.data); - - .tbss (NOLOAD) : { - . = ALIGN(4); - __bss_start__ = .; - __tls_base = .; - *(.tbss .tbss.* .gnu.linkonce.tb.*) - *(.tcommon) - - __tls_end = .; - } > RAM - - .bss (NOLOAD) : { - . = ALIGN(4); - __tbss_end = .; - - *(SORT_BY_ALIGNMENT(SORT_BY_NAME(.bss*))) - *(COMMON) - PROVIDE(__global_pointer$ = . + 2K); - *(.sbss*) - . = ALIGN(4); - __bss_end__ = .; - } > RAM - - .heap (NOLOAD): - { - __end__ = .; - end = __end__; - KEEP(*(.heap*)) - } > RAM - /* historically on GCC sbrk was growing past __HeapLimit to __StackLimit, however - to be more compatible, we now set __HeapLimit explicitly to where the end of the heap is */ - __HeapLimit = ORIGIN(RAM) + LENGTH(RAM); - - /* Start and end symbols must be word-aligned */ - .scratch_x : { - __scratch_x_start__ = .; - *(.scratch_x.*) - . = ALIGN(4); - __scratch_x_end__ = .; - } > SCRATCH_X AT > FLASH - __scratch_x_source__ = LOADADDR(.scratch_x); - - .scratch_y : { - __scratch_y_start__ = .; - *(.scratch_y.*) - . = ALIGN(4); - __scratch_y_end__ = .; - } > SCRATCH_Y AT > FLASH - __scratch_y_source__ = LOADADDR(.scratch_y); - - /* .stack*_dummy section doesn't contains any symbols. It is only - * used for linker to calculate size of stack sections, and assign - * values to stack symbols later - * - * stack1 section may be empty/missing if platform_launch_core1 is not used */ - - /* by default we put core 0 stack at the end of scratch Y, so that if core 1 - * stack is not used then all of SCRATCH_X is free. - */ - .stack1_dummy (NOLOAD): - { - *(.stack1*) - } > SCRATCH_X - .stack_dummy (NOLOAD): - { - KEEP(*(.stack*)) - } > SCRATCH_Y - - .flash_end : { - KEEP(*(.embedded_end_block*)) - PROVIDE(__flash_binary_end = .); - } > FLASH =0xaa - - /* stack limit is poorly named, but historically is maximum heap ptr */ - __StackLimit = ORIGIN(RAM) + LENGTH(RAM); - __StackOneTop = ORIGIN(SCRATCH_X) + LENGTH(SCRATCH_X); - __StackTop = ORIGIN(SCRATCH_Y) + LENGTH(SCRATCH_Y); - __StackOneBottom = __StackOneTop - SIZEOF(.stack1_dummy); - __StackBottom = __StackTop - SIZEOF(.stack_dummy); - PROVIDE(__stack = __StackTop); - - /* picolibc and LLVM */ - PROVIDE (__heap_start = __end__); - PROVIDE (__heap_end = __HeapLimit); - PROVIDE( __tls_align = MAX(ALIGNOF(.tdata), ALIGNOF(.tbss)) ); - PROVIDE( __tls_size_align = (__tls_size + __tls_align - 1) & ~(__tls_align - 1)); - PROVIDE( __arm32_tls_tcb_offset = MAX(8, __tls_align) ); - - /* llvm-libc */ - PROVIDE (_end = __end__); - PROVIDE (__llvm_libc_heap_limit = __HeapLimit); - - /* Check if data + heap + stack exceeds RAM limit */ - ASSERT(__StackLimit >= __HeapLimit, "region RAM overflowed") - - ASSERT( __binary_info_header_end - __logical_binary_start <= 1024, "Binary info must be in first 1024 bytes of the binary") - ASSERT( __embedded_block_end - __logical_binary_start <= 4096, "Embedded block must be in first 4096 bytes of the binary") - - /* todo assert on extra code */ -} - diff --git a/src/platform/PICO/mk/PICO.mk b/src/platform/PICO/mk/PICO.mk deleted file mode 100644 index 699ee8f0fe..0000000000 --- a/src/platform/PICO/mk/PICO.mk +++ /dev/null @@ -1,158 +0,0 @@ -# -# Raspberry PICO Make file include -# - -ifeq ($(DEBUG_HARDFAULTS),PICO) -CFLAGS += -DDEBUG_HARDFAULTS -endif - -SDK_DIR = $(LIB_MAIN_DIR)/pico-sdk - -#CMSIS -CMSIS_DIR := $(SDK_DIR)/rp2_common/cmsis/stub/CMSIS - -#STDPERIPH -STDPERIPH_DIR = $(SDK_SIR) -STDPERIPH_SRC = \ - - -VPATH := $(VPATH):$(STDPERIPH_DIR) - -DEVICE_STDPERIPH_SRC := \ - $(STDPERIPH_SRC) \ - $(USBCORE_SRC) \ - $(USBCDC_SRC) \ - $(USBHID_SRC) \ - $(USBMSC_SRC) - -#CMSIS -VPATH := $(VPATH):$(CMSIS_DIR)/Core/Include:$(CMSIS_DIR)/Device/$(TARGET_MCU)/Include -CMSIS_SRC := - -#SRC -VPATH := $(VPATH):$(STDPERIPH_DIR) - -INCLUDE_DIRS := \ - $(INCLUDE_DIRS) \ - $(TARGET_PLATFORM_DIR) \ - $(TARGET_PLATFORM_DIR)/startup \ - $(SDK_DIR)/$(TARGET_MCU)/pico_platform/include \ - $(SDK_DIR)/$(TARGET_MCU)/hardware_regs/include \ - $(SDK_DIR)/$(TARGET_MCU)/hardware_structs/include \ - $(SDK_DIR)/common/pico_bit_ops_headers/include \ - $(SDK_DIR)/common/pico_base_headers/include \ - $(SDK_DIR)/common/boot_picoboot_headers/include \ - $(SDK_DIR)/common/pico_usb_reset_interface_headers/include \ - $(SDK_DIR)/common/pico_time/include \ - $(SDK_DIR)/common/boot_uf2_headers/include \ - $(SDK_DIR)/common/pico_divider_headers/include \ - $(SDK_DIR)/common/boot_picobin_headers/include \ - $(SDK_DIR)/common/pico_util/include \ - $(SDK_DIR)/common/pico_stdlib_headers/include \ - $(SDK_DIR)/common/hardware_claim/include \ - $(SDK_DIR)/common/pico_binary_info/include \ - $(SDK_DIR)/common/pico_sync/include \ - $(SDK_DIR)/rp2_common/pico_stdio_uart/include \ - $(SDK_DIR)/rp2_common/pico_stdio_usb/include \ - $(SDK_DIR)/rp2_common/pico_stdio_rtt/include \ - $(SDK_DIR)/rp2_common/tinyusb/include \ - $(SDK_DIR)/rp2_common/hardware_rtc/include \ - $(SDK_DIR)/rp2_common/hardware_boot_lock/include \ - $(SDK_DIR)/rp2_common/pico_mem_ops/include \ - $(SDK_DIR)/rp2_common/hardware_exception/include \ - $(SDK_DIR)/rp2_common/hardware_sync_spin_lock/include \ - $(SDK_DIR)/rp2_common/pico_runtime_init/include \ - $(SDK_DIR)/rp2_common/pico_standard_link/include \ - $(SDK_DIR)/rp2_common/hardware_pio/include \ - $(SDK_DIR)/rp2_common/pico_platform_compiler/include \ - $(SDK_DIR)/rp2_common/hardware_divider/include \ - $(SDK_DIR)/rp2_common/pico_bootsel_via_double_reset/include \ - $(SDK_DIR)/rp2_common/hardware_powman/include \ - $(SDK_DIR)/rp2_common/pico_btstack/include \ - $(SDK_DIR)/rp2_common/pico_cyw43_driver/include \ - $(SDK_DIR)/rp2_common/hardware_flash/include \ - $(SDK_DIR)/rp2_common/hardware_ticks/include \ - $(SDK_DIR)/rp2_common/hardware_dma/include \ - $(SDK_DIR)/rp2_common/pico_bit_ops/include \ - $(SDK_DIR)/rp2_common/hardware_clocks/include \ - $(SDK_DIR)/rp2_common/pico_unique_id/include \ - $(SDK_DIR)/rp2_common/hardware_dcp/include \ - $(SDK_DIR)/rp2_common/hardware_watchdog/include \ - $(SDK_DIR)/rp2_common/pico_rand/include \ - $(SDK_DIR)/rp2_common/hardware_hazard3/include \ - $(SDK_DIR)/rp2_common/hardware_uart/include \ - $(SDK_DIR)/rp2_common/hardware_interp/include \ - $(SDK_DIR)/rp2_common/pico_printf/include \ - $(SDK_DIR)/rp2_common/pico_aon_timer/include \ - $(SDK_DIR)/rp2_common/hardware_riscv_platform_timer/include \ - $(SDK_DIR)/rp2_common/pico_double/include \ - $(SDK_DIR)/rp2_common/pico_cyw43_arch/include \ - $(SDK_DIR)/rp2_common/hardware_vreg/include \ - $(SDK_DIR)/rp2_common/pico_mbedtls/include \ - $(SDK_DIR)/rp2_common/hardware_spi/include \ - $(SDK_DIR)/rp2_common/hardware_rcp/include \ - $(SDK_DIR)/rp2_common/hardware_riscv/include \ - $(SDK_DIR)/rp2_common/pico_standard_binary_info/include \ - $(SDK_DIR)/rp2_common/pico_i2c_slave/include \ - $(SDK_DIR)/rp2_common/pico_int64_ops/include \ - $(SDK_DIR)/rp2_common/pico_sha256/include \ - $(SDK_DIR)/rp2_common/hardware_irq/include \ - $(SDK_DIR)/rp2_common/pico_divider/include \ - $(SDK_DIR)/rp2_common/pico_flash/include \ - $(SDK_DIR)/rp2_common/hardware_sync/include \ - $(SDK_DIR)/rp2_common/pico_bootrom/include \ - $(SDK_DIR)/rp2_common/pico_crt0/include \ - $(SDK_DIR)/rp2_common/pico_clib_interface/include \ - $(SDK_DIR)/rp2_common/pico_stdio/include \ - $(SDK_DIR)/rp2_common/pico_runtime/include \ - $(SDK_DIR)/rp2_common/pico_time_adapter/include \ - $(SDK_DIR)/rp2_common/pico_platform_panic/include \ - $(SDK_DIR)/rp2_common/hardware_adc/include \ - $(SDK_DIR)/rp2_common/cmsis/include \ - $(SDK_DIR)/rp2_common/hardware_pll/include \ - $(SDK_DIR)/rp2_common/pico_platform_sections/include \ - $(SDK_DIR)/rp2_common/boot_bootrom_headers/include \ - $(SDK_DIR)/rp2_common/pico_fix/include \ - $(SDK_DIR)/rp2_common/pico_lwip/include \ - $(SDK_DIR)/rp2_common/hardware_base/include \ - $(SDK_DIR)/rp2_common/hardware_xosc/include \ - $(SDK_DIR)/rp2_common/pico_async_context/include \ - $(SDK_DIR)/rp2_common/hardware_pwm/include \ - $(SDK_DIR)/rp2_common/pico_stdio_semihosting/include \ - $(SDK_DIR)/rp2_common/pico_float/include \ - $(SDK_DIR)/rp2_common/hardware_resets/include \ - $(SDK_DIR)/rp2_common/pico_cxx_options/include \ - $(SDK_DIR)/rp2_common/pico_stdlib/include \ - $(SDK_DIR)/rp2_common/hardware_sha256/include \ - $(SDK_DIR)/rp2_common/hardware_i2c/include \ - $(SDK_DIR)/rp2_common/pico_atomic/include \ - $(SDK_DIR)/rp2_common/pico_multicore/include \ - $(SDK_DIR)/rp2_common/hardware_gpio/include \ - $(SDK_DIR)/rp2_common/pico_malloc/include \ - $(SDK_DIR)/rp2_common/hardware_timer/include \ - $(CMSIS_DIR)/Core/Include \ - $(CMSIS_DIR)/Device/$(TARGET_MCU)/Include - -#Flags -ARCH_FLAGS = -mthumb -mcpu=cortex-m33 -march=armv8-m.main+fp+dsp -mfloat-abi=softfp -mcmse - -DEVICE_FLAGS = - -ifeq ($(TARGET_MCU),RP2350) -DEVICE_FLAGS += -DRP2350 -DLIB_BOOT_STAGE2_HEADERS=1 -DLIB_PICO_ATOMIC=1 -DLIB_PICO_BIT_OPS=1 -DLIB_PICO_BIT_OPS_PICO=1 -DLIB_PICO_CLIB_INTERFACE=1 -DLIB_PICO_CRT0=1 -DLIB_PICO_CXX_OPTIONS=1 -DLIB_PICO_DIVIDER=1 -DLIB_PICO_DIVIDER_COMPILER=1 -DLIB_PICO_DOUBLE=1 -DLIB_PICO_DOUBLE_PICO=1 -DLIB_PICO_FLOAT=1 -DLIB_PICO_FLOAT_PICO=1 -DLIB_PICO_FLOAT_PICO_VFP=1 -DLIB_PICO_INT64_OPS=1 -DLIB_PICO_INT64_OPS_COMPILER=1 -DLIB_PICO_MALLOC=1 -DLIB_PICO_MEM_OPS=1 -DLIB_PICO_MEM_OPS_COMPILER=1 -DLIB_PICO_NEWLIB_INTERFACE=1 -DLIB_PICO_PLATFORM=1 -DLIB_PICO_PLATFORM_COMPILER=1 -DLIB_PICO_PLATFORM_PANIC=1 -DLIB_PICO_PLATFORM_SECTIONS=1 -DLIB_PICO_PRINTF=1 -DLIB_PICO_PRINTF_PICO=1 -DLIB_PICO_RUNTIME=1 -DLIB_PICO_RUNTIME_INIT=1 -DLIB_PICO_STANDARD_BINARY_INFO=1 -DLIB_PICO_STANDARD_LINK=1 -DLIB_PICO_STDIO=1 -DLIB_PICO_STDIO_UART=1 -DLIB_PICO_STDLIB=1 -DLIB_PICO_SYNC=1 -DLIB_PICO_SYNC_CRITICAL_SECTION=1 -DLIB_PICO_SYNC_MUTEX=1 -DLIB_PICO_SYNC_SEM=1 -DLIB_PICO_TIME=1 -DLIB_PICO_TIME_ADAPTER=1 -DLIB_PICO_UTIL=1 -DPICO_32BIT=1 -DPICO_BUILD=1 -DPICO_COPY_TO_RAM=0 -DPICO_CXX_ENABLE_EXCEPTIONS=0 -DPICO_NO_FLASH=0 -DPICO_NO_HARDWARE=0 -DPICO_ON_DEVICE=1 -DPICO_RP2350=1 -DPICO_USE_BLOCKED_RAM=0 -LD_SCRIPT = $(LINKER_DIR)/pico_rp2350.ld -STARTUP_SRC = startup/bs2_default_padded_checksummed.S -MCU_FLASH_SIZE = 4096 -# Override the OPTIMISE_SPEED compiler setting to save flash space on these 512KB targets. -# Performance is only slightly affected but around 50 kB of flash are saved. -OPTIMISE_SPEED = -O2 -else -$(error Unknown MCU for Raspberry PICO target) -endif - -DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DPICO - -MCU_COMMON_SRC = \ - - -DEVICE_FLAGS += diff --git a/src/platform/PICO/platform_mcu.h b/src/platform/PICO/platform_mcu.h deleted file mode 100644 index 253dddd054..0000000000 --- a/src/platform/PICO/platform_mcu.h +++ /dev/null @@ -1,67 +0,0 @@ -/* - * This file is part of Betaflight. - * - * Betaflight is free software. You can redistribute this software - * and/or modify this software under the terms of the GNU General - * Public License as published by the Free Software Foundation, - * either version 3 of the License, or (at your option) any later - * version. - * - * Betaflight is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public - * License along with this software. - * - * If not, see . - */ - -#pragma once - -#if defined(RP2350) - -#include "RP2350.h" - -typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState; - -#define I2C_TypeDef I2C0_Type -//#define I2C_HandleTypeDef -#define GPIO_TypeDef IO_BANK0_Type -//#define GPIO_InitTypeDef -#define TIM_TypeDef TIMER0_Type -//#define TIM_OCInitTypeDef -#define DMA_TypeDef DMA_Type -//#define DMA_InitTypeDef -//#define DMA_Channel_TypeDef -#define SPI_TypeDef SPI0_Type -#define ADC_TypeDef ADC_Type -#define USART_TypeDef UART0_Type -#define TIM_OCInitTypeDef TIMER0_Type -#define TIM_ICInitTypeDef TIMER0_Type -//#define TIM_OCStructInit -//#define TIM_Cmd -//#define TIM_CtrlPWMOutputs -//#define TIM_TimeBaseInit -//#define TIM_ARRPreloadConfig -//#define SystemCoreClock -//#define EXTI_TypeDef -//#define EXTI_InitTypeDef - - -#endif - -#define DEFAULT_CPU_OVERCLOCK 0 -#define TASK_GYROPID_DESIRED_PERIOD 125 // 125us = 8kHz -#define SCHEDULER_DELAY_LIMIT 10 - -#define IOCFG_OUT_PP 0 -#define IOCFG_OUT_OD 0 -#define IOCFG_AF_PP 0 -#define IOCFG_AF_OD 0 -#define IOCFG_IPD 0 -#define IOCFG_IPU 0 -#define IOCFG_IN_FLOATING 0 - diff --git a/src/platform/PICO/startup/bs2_default_padded_checksummed.S b/src/platform/PICO/startup/bs2_default_padded_checksummed.S deleted file mode 100644 index 124bd8d265..0000000000 --- a/src/platform/PICO/startup/bs2_default_padded_checksummed.S +++ /dev/null @@ -1,25 +0,0 @@ -// Padded and checksummed version of: /home/black/src/pico/hello/build/pico-sdk/src/rp2350/boot_stage2/bs2_default.bin - -.cpu cortex-m0plus -.thumb - -.section .boot2, "ax" - -.global __boot2_entry_point -__boot2_entry_point: -.byte 0x00, 0xb5, 0x24, 0x4b, 0x21, 0x20, 0x58, 0x60, 0x13, 0xf5, 0x40, 0x53, 0x02, 0x20, 0x98, 0x60 -.byte 0xd8, 0x60, 0x18, 0x61, 0x58, 0x61, 0x13, 0xf5, 0x0d, 0x23, 0x1f, 0x49, 0x19, 0x60, 0x18, 0x68 -.byte 0x10, 0xf0, 0x02, 0x0f, 0xfb, 0xd1, 0x35, 0x20, 0x00, 0xf0, 0x2c, 0xf8, 0x02, 0x28, 0x14, 0xd0 -.byte 0x06, 0x20, 0x58, 0x60, 0x00, 0xf0, 0x22, 0xf8, 0x98, 0x68, 0x01, 0x20, 0x58, 0x60, 0x00, 0x20 -.byte 0x58, 0x60, 0x02, 0x20, 0x58, 0x60, 0x00, 0xf0, 0x19, 0xf8, 0x98, 0x68, 0x98, 0x68, 0x98, 0x68 -.byte 0x05, 0x20, 0x00, 0xf0, 0x17, 0xf8, 0x40, 0x08, 0xfa, 0xd2, 0x31, 0xf0, 0x01, 0x01, 0x19, 0x60 -.byte 0x0e, 0x48, 0xd8, 0x60, 0x4a, 0xf2, 0xeb, 0x00, 0x58, 0x61, 0x0d, 0x48, 0x18, 0x61, 0x4f, 0xf0 -.byte 0xa0, 0x51, 0x09, 0x78, 0x20, 0xf4, 0x80, 0x50, 0x18, 0x61, 0x00, 0xbd, 0x18, 0x68, 0x80, 0x08 -.byte 0xfc, 0xd2, 0x70, 0x47, 0x00, 0xb5, 0x58, 0x60, 0x58, 0x60, 0xff, 0xf7, 0xf7, 0xff, 0x98, 0x68 -.byte 0x98, 0x68, 0x00, 0xbd, 0x00, 0x00, 0x04, 0x40, 0x41, 0x00, 0x80, 0x07, 0x02, 0x02, 0x00, 0x40 -.byte 0xa8, 0x92, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 -.byte 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 -.byte 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 -.byte 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 -.byte 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 -.byte 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 diff --git a/src/platform/PICO/target/RP2350/.exclude b/src/platform/PICO/target/RP2350/.exclude deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/src/platform/PICO/target/RP2350/target.h b/src/platform/PICO/target/RP2350/target.h deleted file mode 100644 index f7b9076ccc..0000000000 --- a/src/platform/PICO/target/RP2350/target.h +++ /dev/null @@ -1,69 +0,0 @@ -/* - * This file is part of Betaflight. - * - * Betaflight is free software. You can redistribute this software - * and/or modify this software under the terms of the GNU General - * Public License as published by the Free Software Foundation, - * either version 3 of the License, or (at your option) any later - * version. - * - * Betaflight is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public - * License along with this software. - * - * If not, see . - */ - -#pragma once - -#ifndef TARGET_BOARD_IDENTIFIER -#define TARGET_BOARD_IDENTIFIER "R235" -#endif - -#ifndef USBD_PRODUCT_STRING -#define USBD_PRODUCT_STRING "Betaflight RP2350" -#endif - -#undef USE_DMA -#undef USE_FLASH -#undef USE_FLASH_CHIP - -#undef USE_TIMER -#undef USE_SPI -#undef USE_I2C -#undef USE_UART -#undef USE_DSHOT -#undef USE_RCC - -#define GPIOA_BASE ((intptr_t)0x0001) - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTE 0xffff -#define TARGET_IO_PORTF 0xffff - -#undef USE_FLASH -#undef USE_FLASH_CHIP -#undef USE_FLASH_M25P16 -#undef USE_FLASH_W25N01G -#undef USE_FLASH_W25N02K -#undef USE_FLASH_W25M -#undef USE_FLASH_W25M512 -#undef USE_FLASH_W25M02G -#undef USE_FLASH_W25Q128FV -#undef USE_FLASH_PY25Q128HA -#undef USE_FLASH_W25Q64FV - -#define FLASH_PAGE_SIZE 0x1000 -#define CONFIG_IN_RAM - -#define U_ID_0 0 -#define U_ID_1 1 -#define U_ID_2 2 diff --git a/src/platform/PICO/target/RP2350/target.mk b/src/platform/PICO/target/RP2350/target.mk deleted file mode 100644 index 94f4209a29..0000000000 --- a/src/platform/PICO/target/RP2350/target.mk +++ /dev/null @@ -1,2 +0,0 @@ -TARGET_MCU := RP2350 -TARGET_MCU_FAMILY := PICO From 5f539935eaf3ea25e5546cfa8a361effdb0a39a0 Mon Sep 17 00:00:00 2001 From: "Git bot (blckmn)" Date: Sat, 31 May 2025 06:25:03 +0000 Subject: [PATCH 6/8] Auto updated submodule references [31-05-2025] --- src/config | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/config b/src/config index 0ce3bf0f2c..eda6b30999 160000 --- a/src/config +++ b/src/config @@ -1 +1 @@ -Subproject commit 0ce3bf0f2c3749e93866a640f2af3fd6754db824 +Subproject commit eda6b309994923772eeab82fce3d6d8c3c0812a2 From f26efcc622b2b07c0c87a1bf7df8796c9903712d Mon Sep 17 00:00:00 2001 From: Mark Haslinghuis Date: Sat, 31 May 2025 11:38:35 +0200 Subject: [PATCH 7/8] Fix ICM40609D reset register (#14415) --- src/main/drivers/accgyro/accgyro_spi_icm40609.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/accgyro/accgyro_spi_icm40609.c b/src/main/drivers/accgyro/accgyro_spi_icm40609.c index 5ed6c8eb73..ed45cdb668 100644 --- a/src/main/drivers/accgyro/accgyro_spi_icm40609.c +++ b/src/main/drivers/accgyro/accgyro_spi_icm40609.c @@ -243,7 +243,7 @@ #define ICM40609_ACCEL_DATA_X1_UI 0x1F #define ICM40609_GYRO_DATA_X1_UI 0x25 -#define ICM40609_RESET_REG 0x4C +#define ICM40609_RESET_REG 0x11 #define ICM40609_SOFT_RESET_VAL 0x01 #ifndef ICM40609_LOCK From 1dcc61138813a9e0f20f01664f7b7cae66f97957 Mon Sep 17 00:00:00 2001 From: Jay Blackman Date: Sun, 1 Jun 2025 04:53:54 +1000 Subject: [PATCH 8/8] PICO: Makefile uf2 support using picotool (#14402) * Adding picotool build recipe in makefiles. * Use semaphore in directory for default goal recipe for target * Suggestions from coderabbitai * Further coderabbit suggestions * Wrong case * Minor change to improve logic * Further improvements. - submodules replaced with specific submodule for pico_sdk (to avoid all developers needing this) * Removing need for remote on git submodule update for configs, as we have the commit occurring daily. - made sure config also build uf2 * Simplified firmware output selection for target * Moved UF2 outside of EXST * Missed two remnants of HEX_TARGETS * Adding check for target * As target is known default output can be set in platform mk file or target mk file - no need for file indicator (i.e. .exe or .uf2) * Update config.mk for less verbosity --- Makefile | 141 +++++++++++++++++------------- mk/build_verbosity.mk | 1 + mk/config.mk | 12 +-- mk/tools.mk | 51 +++++++++++ src/platform/SIMULATOR/mk/SITL.mk | 4 + 5 files changed, 142 insertions(+), 67 deletions(-) diff --git a/Makefile b/Makefile index 7be4e6a6d2..c6d2c6463d 100644 --- a/Makefile +++ b/Makefile @@ -15,7 +15,7 @@ # Things that the user might override on the commandline # -# The target to build, see BASE_TARGETS/EXE_TARGETS below +# The target or config to build TARGET ?= CONFIG ?= @@ -57,7 +57,11 @@ CFLAGS_DISABLED := FORKNAME = betaflight # Working directories +# ROOT_DIR is the full path to the directory containing this Makefile +ROOT_DIR := $(realpath $(dir $(abspath $(lastword $(MAKEFILE_LIST))))) +# ROOT is the relative path to the directory containing this Makefile ROOT := $(patsubst %/,%,$(dir $(lastword $(MAKEFILE_LIST)))) + PLATFORM_DIR := $(ROOT)/src/platform SRC_DIR := $(ROOT)/src/main LIB_MAIN_DIR := $(ROOT)/lib/main @@ -90,12 +94,9 @@ MAKE_PARALLEL = $(if $(filter -j%, $(MAKEFLAGS)),$(EMPTY),-j$(DEFAULT_PAR # pre-build sanity checks include $(MAKE_SCRIPT_DIR)/checks.mk -# list of targets that are executed on host (using exe as goal) -EXE_TARGETS := SITL - # basic target list PLATFORMS := $(sort $(notdir $(patsubst /%,%, $(wildcard $(PLATFORM_DIR)/*)))) -BASE_TARGETS := $(filter-out $(EXE_TARGETS),$(sort $(notdir $(patsubst %/,%,$(dir $(wildcard $(PLATFORM_DIR)/*/target/*/target.mk)))))) +BASE_TARGETS := $(sort $(notdir $(patsubst %/,%,$(dir $(wildcard $(PLATFORM_DIR)/*/target/*/target.mk))))) # configure some directories that are relative to wherever ROOT_DIR is located TOOLS_DIR ?= $(ROOT)/tools @@ -126,7 +127,7 @@ FC_VER_PATCH := $(shell grep " FC_VERSION_PATCH" src/main/build/version.h | awk FC_VER := $(FC_VER_MAJOR).$(FC_VER_MINOR).$(FC_VER_PATCH) -# import config handling +# import config handling (must occur after the hydration of hex, exe and uf2 targets) include $(MAKE_SCRIPT_DIR)/config.mk # default xtal value @@ -134,7 +135,7 @@ HSE_VALUE ?= 8000000 CI_EXCLUDED_TARGETS := $(sort $(notdir $(patsubst %/,%,$(dir $(wildcard $(PLATFORM_DIR)/*/target/*/.exclude))))) CI_COMMON_TARGETS := STM32F4DISCOVERY CRAZYBEEF4SX1280 CRAZYBEEF4FR MATEKF405TE AIRBOTG4AIO TBS_LUCID_FC IFLIGHT_BLITZ_F722 NUCLEOF446 SPRACINGH7EXTREME SPRACINGH7RF -CI_TARGETS := $(filter-out $(CI_EXCLUDED_TARGETS), $(BASE_TARGETS) $(EXE_TARGETS)) $(filter $(CI_COMMON_TARGETS), $(BASE_CONFIGS)) +CI_TARGETS := $(filter-out $(CI_EXCLUDED_TARGETS), $(BASE_TARGETS) $(filter $(CI_COMMON_TARGETS), $(BASE_CONFIGS))) PREVIEW_TARGETS := MATEKF411 AIKONF4V2 AIRBOTG4AIO ZEEZF7V3 FOXEERF745V4_AIO KAKUTEH7 TBS_LUCID_FC SITL SPRACINGH7EXTREME SPRACINGH7RF TARGET_PLATFORM := $(notdir $(patsubst %/,%,$(subst target/$(TARGET)/,, $(dir $(wildcard $(PLATFORM_DIR)/*/target/$(TARGET)/target.mk))))) @@ -142,7 +143,8 @@ TARGET_PLATFORM_DIR := $(PLATFORM_DIR)/$(TARGET_PLATFORM) LINKER_DIR := $(TARGET_PLATFORM_DIR)/link ifneq ($(TARGET),) -include $(TARGET_PLATFORM_DIR)/target/$(TARGET)/target.mk +TARGET_DIR = $(TARGET_PLATFORM_DIR)/target/$(TARGET) +include $(TARGET_DIR)/target.mk endif REVISION := norevision @@ -221,24 +223,17 @@ ifneq ($(HSE_VALUE),) DEVICE_FLAGS := $(DEVICE_FLAGS) -DHSE_VALUE=$(HSE_VALUE) endif -TARGET_DIR = $(TARGET_PLATFORM_DIR)/target/$(TARGET) endif # TARGET specified +ifeq ($(or $(CONFIG),$(TARGET)),) +.DEFAULT_GOAL := all +else +.DEFAULT_GOAL := fwo +endif + # openocd specific includes include $(MAKE_SCRIPT_DIR)/openocd.mk -ifeq ($(CONFIG),) -ifeq ($(TARGET),) -.DEFAULT_GOAL := all -else ifneq ($(filter $(TARGET),$(EXE_TARGETS)),) -.DEFAULT_GOAL := exe -else -.DEFAULT_GOAL := hex -endif -else # ifeq ($(CONFIG),) -.DEFAULT_GOAL := hex -endif - INCLUDE_DIRS := $(INCLUDE_DIRS) \ $(ROOT)/lib/main/MAVLink @@ -364,6 +359,12 @@ CPPCHECK = cppcheck $(CSOURCES) --enable=all --platform=unix64 \ $(addprefix -isystem,$(SYS_INCLUDE_DIRS)) \ -I/usr/include -I/usr/include/linux +ifneq ($(filter fwo hex uf2 bin elf zip, $(MAKECMDGOALS)),) + ifeq ($(TARGET),) + $(error "You must specify a target to build.") + endif +endif + TARGET_NAME := $(TARGET) ifneq ($(CONFIG),) @@ -378,21 +379,22 @@ TARGET_FULLNAME = $(FORKNAME)_$(FC_VER)_$(TARGET_NAME) # # Things we will build # -TARGET_BIN = $(BIN_DIR)/$(TARGET_FULLNAME).bin -TARGET_HEX = $(BIN_DIR)/$(TARGET_FULLNAME).hex -TARGET_EXE = $(BIN_DIR)/$(TARGET_FULLNAME) -TARGET_DFU = $(BIN_DIR)/$(TARGET_FULLNAME).dfu -TARGET_ZIP = $(BIN_DIR)/$(TARGET_FULLNAME).zip -TARGET_OBJ_DIR = $(OBJECT_DIR)/$(TARGET_NAME) -TARGET_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME).elf -TARGET_EXST_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME)_EXST.elf -TARGET_UNPATCHED_BIN = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME)_UNPATCHED.bin -TARGET_LST = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME).lst -TARGET_OBJS = $(addsuffix .o,$(addprefix $(TARGET_OBJ_DIR)/,$(basename $(SRC)))) -TARGET_DEPS = $(addsuffix .d,$(addprefix $(TARGET_OBJ_DIR)/,$(basename $(SRC)))) -TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME).map +TARGET_BIN := $(BIN_DIR)/$(TARGET_FULLNAME).bin +TARGET_HEX := $(BIN_DIR)/$(TARGET_FULLNAME).hex +TARGET_UF2 := $(BIN_DIR)/$(TARGET_FULLNAME).uf2 +TARGET_EXE := $(BIN_DIR)/$(TARGET_FULLNAME) +TARGET_DFU := $(BIN_DIR)/$(TARGET_FULLNAME).dfu +TARGET_ZIP := $(BIN_DIR)/$(TARGET_FULLNAME).zip +TARGET_OBJ_DIR := $(OBJECT_DIR)/$(TARGET_NAME) +TARGET_ELF := $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME).elf +TARGET_EXST_ELF := $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME)_EXST.elf +TARGET_UNPATCHED_BIN := $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME)_UNPATCHED.bin +TARGET_LST := $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME).lst +TARGET_OBJS := $(addsuffix .o,$(addprefix $(TARGET_OBJ_DIR)/,$(basename $(SRC)))) +TARGET_DEPS := $(addsuffix .d,$(addprefix $(TARGET_OBJ_DIR)/,$(basename $(SRC)))) +TARGET_MAP := $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME).map -TARGET_EXST_HASH_SECTION_FILE = $(TARGET_OBJ_DIR)/exst_hash_section.bin +TARGET_EXST_HASH_SECTION_FILE := $(TARGET_OBJ_DIR)/exst_hash_section.bin ifeq ($(DEBUG_MIXED),yes) TARGET_EF_HASH := $(shell echo -n -- "$(EXTRA_FLAGS)" "$(OPTIONS)" "$(DEVICE_FLAGS)" "$(TARGET_FLAGS)" | openssl dgst -md5 -r | awk '{print $$1;}') @@ -407,6 +409,7 @@ CLEAN_ARTIFACTS += $(TARGET_HEX_REV) $(TARGET_HEX) CLEAN_ARTIFACTS += $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP) CLEAN_ARTIFACTS += $(TARGET_LST) CLEAN_ARTIFACTS += $(TARGET_DFU) +CLEAN_ARTIFACTS += $(TARGET_UF2) # Make sure build date and revision is updated on every incremental build $(TARGET_OBJ_DIR)/build/version.o : $(SRC) @@ -482,8 +485,12 @@ $(TARGET_ELF): $(TARGET_OBJS) $(LD_SCRIPT) $(LD_SCRIPTS) $(V1) $(CROSS_CC) -o $@ $(filter-out %.ld,$^) $(LD_FLAGS) $(V1) $(SIZE) $(TARGET_ELF) +$(TARGET_UF2): $(TARGET_ELF) + @echo "Creating UF2 $(TARGET_UF2)" "$(STDOUT)" + $(V1) $(PICOTOOL) uf2 convert $< $@ || { echo "Failed to convert ELF to UF2 format"; exit 1; } + $(TARGET_EXE): $(TARGET_ELF) - @echo Copy $< to $@ "$(STDOUT)" + @echo "Creating exe - copying $< to $@" "$(STDOUT)" $(V1) cp $< $@ # Compile @@ -539,17 +546,11 @@ $(TARGET_OBJ_DIR)/%.o: %.S ## all : Build all currently built targets all: $(CI_TARGETS) +.PHONY: $(BASE_TARGETS) $(BASE_TARGETS): - $(V0) @echo "Building target $@" && \ - $(MAKE) hex TARGET=$@ && \ - echo "Building $@ succeeded." + $(MAKE) fwo TARGET=$@ -$(EXE_TARGETS): - $(V0) @echo "Building executable target $@" && \ - $(MAKE) exe TARGET=$@ && \ - echo "Building $@ succeeded." - -TARGETS_CLEAN = $(addsuffix _clean,$(BASE_TARGETS) $(EXE_TARGETS)) +TARGETS_CLEAN = $(addsuffix _clean,$(BASE_TARGETS)) CONFIGS_CLEAN = $(addsuffix _clean,$(BASE_CONFIGS)) @@ -625,39 +626,56 @@ endif TARGETS_ZIP = $(addsuffix _zip,$(BASE_TARGETS)) ## _zip : build target and zip it (useful for posting to GitHub) +.PHONY: $(TARGETS_ZIP) $(TARGETS_ZIP): - $(V0) $(MAKE) hex TARGET=$(subst _zip,,$@) - $(V0) $(MAKE) zip TARGET=$(subst _zip,,$@) + $(V1) $(MAKE) $(MAKE_PARALLEL) zip TARGET=$(subst _zip,,$@) -zip: - $(V0) zip $(TARGET_ZIP) $(TARGET_HEX) +.PHONY: zip +zip: $(TARGET_HEX) + $(V1) zip $(TARGET_ZIP) $(TARGET_HEX) +.PHONY: binary binary: - $(V0) $(MAKE) $(MAKE_PARALLEL) $(TARGET_BIN) + $(V1) $(MAKE) $(MAKE_PARALLEL) $(TARGET_BIN) +.PHONY: hex hex: - $(V0) $(MAKE) $(MAKE_PARALLEL) $(TARGET_HEX) + $(V1) $(MAKE) $(MAKE_PARALLEL) $(TARGET_HEX) -.phony: exe +.PHONY: uf2 +uf2: + $(V1) $(MAKE) $(MAKE_PARALLEL) $(TARGET_UF2) + +.PHONY: exe exe: $(TARGET_EXE) -TARGETS_REVISION = $(addsuffix _rev,$(BASE_TARGETS)) +# FWO (Firmware Output) is the default output for building the firmware +.PHONY: fwo +fwo: +ifeq ($(DEFAULT_OUTPUT),exe) + $(V1) $(MAKE) exe +else ifeq ($(DEFAULT_OUTPUT),uf2) + $(V1) $(MAKE) uf2 +else + $(V1) $(MAKE) hex +endif + +TARGETS_REVISION = $(addsuffix _rev, $(BASE_TARGETS)) ## _rev : build target and add revision to filename +.PHONY: $(TARGETS_REVISION) $(TARGETS_REVISION): - $(V0) $(MAKE) hex REV=yes TARGET=$(subst _rev,,$@) + $(V1) $(MAKE) fwo REV=yes TARGET=$(subst _rev,,$@) -EXE_TARGETS_REVISION = $(addsuffix _rev,$(EXE_TARGETS)) -## _rev : build executable target and add revision to filename -$(EXE_TARGETS_REVISION): - $(V0) $(MAKE) exe REV=yes TARGET=$(subst _rev,,$@) - -all_rev: $(addsuffix _rev,$(CI_TARGETS)) +.PHONY: all_rev +all_rev: $(addsuffix _rev, $(CI_TARGETS)) +.PHONY: unbrick_$(TARGET) unbrick_$(TARGET): $(TARGET_HEX) $(V0) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon $(V0) stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) ## unbrick : unbrick flight controller +.PHONY: unbrick unbrick: unbrick_$(TARGET) ## cppcheck : run static analysis on C source code @@ -690,7 +708,7 @@ help: Makefile mk/tools.mk @echo "To populate configuration targets:" @echo " make configs" @echo "" - @echo "Valid TARGET values are: $(EXE_TARGETS) $(BASE_TARGETS)" + @echo "Valid TARGET values are: $(BASE_TARGETS)" @echo "" @sed -n 's/^## //p' $? @@ -698,7 +716,6 @@ help: Makefile mk/tools.mk targets: @echo "Platforms: $(PLATFORMS)" @echo "Valid targets: $(BASE_TARGETS)" - @echo "Executable targets: $(EXE_TARGETS)" @echo "Built targets: $(CI_TARGETS)" @echo "Default target: $(TARGET)" @echo "CI common targets: $(CI_COMMON_TARGETS)" diff --git a/mk/build_verbosity.mk b/mk/build_verbosity.mk index 9d2f5dc3f3..c1c6206b43 100644 --- a/mk/build_verbosity.mk +++ b/mk/build_verbosity.mk @@ -9,6 +9,7 @@ ifndef V export V0 := export V1 := $(AT) export STDOUT := +export MAKE := $(MAKE) --no-print-directory else ifeq ($(V), 0) export V0 := $(AT) export V1 := $(AT) diff --git a/mk/config.mk b/mk/config.mk index 5f85d4987d..d1c9e54c65 100644 --- a/mk/config.mk +++ b/mk/config.mk @@ -57,21 +57,23 @@ endif #config .PHONY: configs configs: ifeq ($(shell realpath $(CONFIG_DIR)),$(shell realpath $(CONFIGS_SUBMODULE_DIR))) - git submodule update --init --remote -- $(CONFIGS_SUBMODULE_DIR) + @echo "Updating config submodule: $(CONFIGS_SUBMODULE_DIR)" + $(V1) git submodule update --init -- $(CONFIGS_SUBMODULE_DIR) || { echo "Config submodule update failed. Please check your git configuration."; exit 1; } + @echo "Submodule update succeeded." else ifeq ($(wildcard $(CONFIG_DIR)),) @echo "Hydrating clone for configs: $(CONFIG_DIR)" - $(V0) git clone $(CONFIGS_REPO_URL) $(CONFIG_DIR) + $(V1) git clone $(CONFIGS_REPO_URL) $(CONFIG_DIR) else - $(V0) git -C $(CONFIG_DIR) pull origin + $(V1) git -C $(CONFIG_DIR) pull origin endif endif $(BASE_CONFIGS): @echo "Building target config $@" - $(V0) $(MAKE) $(MAKE_PARALLEL) hex CONFIG=$@ + $(V0) $(MAKE) fwo CONFIG=$@ @echo "Building target config $@ succeeded." ## _rev : build configured target and add revision to filename $(addsuffix _rev,$(BASE_CONFIGS)): - $(V0) $(MAKE) $(MAKE_PARALLEL) hex CONFIG=$(subst _rev,,$@) REV=yes + $(V0) $(MAKE) fwo CONFIG=$(subst _rev,,$@) REV=yes diff --git a/mk/tools.mk b/mk/tools.mk index 3dc42ab47a..0b53aedecb 100644 --- a/mk/tools.mk +++ b/mk/tools.mk @@ -331,3 +331,54 @@ breakpad_clean: $(V1) [ ! -d "$(BREAKPAD_DIR)" ] || $(RM) -rf $(BREAKPAD_DIR) @echo " CLEAN $(BREAKPAD_DL_FILE)" $(V1) $(RM) -f $(BREAKPAD_DL_FILE) + +# Raspberry Pi Pico tools +PICOTOOL_REPO := https://github.com/raspberrypi/picotool.git +PICOTOOL_DL_DIR := $(DL_DIR)/picotool +PICOTOOL_BUILD_DIR := $(PICOTOOL_DL_DIR)/build +PICOTOOL_DIR := $(TOOLS_DIR)/picotool +PICO_SDK_PATH ?= $(ROOT_DIR)/lib/main/pico-sdk +PICOTOOL ?= $(PICOTOOL_DIR)/picotool + +ifneq ($(filter picotool_install uf2,$(MAKECMDGOALS)),) + ifeq ($(wildcard $(PICO_SDK_PATH)/CMakeLists.txt),) + $(error "PICO_SDK_PATH ($(PICO_SDK_PATH)) does not point to a valid Pico SDK. Please 'make pico_sdk' to hydrate the Pico SDK.") + endif +endif + +ifneq ($(filter uf2,$(MAKECMDGOALS)),) + ifeq (,$(wildcard $(PICOTOOL))) + ifeq (,$(shell which picotool 2>/dev/null)) + $(error "picotool not in the PATH or configured. Run 'make picotool_install' to install in the tools folder.") + else + PICOTOOL := picotool + endif + endif +endif + +.PHONY: pico_sdk +pico_sdk: + @echo "Updating pico-sdk" + $(V1) git submodule update --init --recursive -- lib/main/pico-sdk || { echo "Failed to update pico-sdk"; exit 1; } + @echo "pico-sdk updated" + +.PHONY: picotool_install +picotool_install: | $(DL_DIR) $(TOOLS_DIR) +picotool_install: picotool_clean + @echo "\n CLONE $(PICOTOOL_REPO)" + $(V1) git clone --depth 1 $(PICOTOOL_REPO) "$(PICOTOOL_DL_DIR)" || { echo "Failed to clone picotool repository"; exit 1; } + @echo "\n BUILD $(PICOTOOL_BUILD_DIR)" + $(V1) [ -d "$(PICOTOOL_DIR)" ] || mkdir -p $(PICOTOOL_DIR) + $(V1) [ -d "$(PICOTOOL_BUILD_DIR)" ] || mkdir -p $(PICOTOOL_BUILD_DIR) + $(V1) cmake -S $(PICOTOOL_DL_DIR) -B $(PICOTOOL_BUILD_DIR) -D PICO_SDK_PATH=$(PICO_SDK_PATH) || { echo "CMake configuration failed"; exit 1; } + $(V1) $(MAKE) -C $(PICOTOOL_BUILD_DIR) || { echo "picotool build failed"; exit 1; } + $(V1) cp $(PICOTOOL_BUILD_DIR)/picotool $(PICOTOOL_DIR)/picotool || { echo "Failed to install picotool binary"; exit 1; } + @echo "\n VERSION:" + $(V1) $(PICOTOOL_DIR)/picotool version + +.PHONY: picotool_clean +picotool_clean: + @echo " CLEAN $(PICOTOOL_DIR)" + $(V1) [ ! -d "$(PICOTOOL_DIR)" ] || $(RM) -rf $(PICOTOOL_DIR) + @echo " CLEAN $(PICOTOOL_DL_DIR)" + $(V1) [ ! -d "$(PICOTOOL_DL_DIR)" ] || $(RM) -rf $(PICOTOOL_DL_DIR) diff --git a/src/platform/SIMULATOR/mk/SITL.mk b/src/platform/SIMULATOR/mk/SITL.mk index 989306556f..757b0e4da8 100644 --- a/src/platform/SIMULATOR/mk/SITL.mk +++ b/src/platform/SIMULATOR/mk/SITL.mk @@ -1,3 +1,7 @@ +# SITL Makefile for the simulator platform + +# Default output is an exe file +DEFAULT_OUTPUT := exe INCLUDE_DIRS := \ $(INCLUDE_DIRS) \