From cf72b156d2ce252e6810b99c918471da36c2e96c Mon Sep 17 00:00:00 2001 From: 488_MP-4 <488_MP-4@iastate.edu> Date: Fri, 5 Apr 2024 05:53:18 +0200 Subject: [PATCH] firmware commented out --- .../config/FreeRTOSConfig.h | 1 - .../drivers/src/test/activeMarkerUartTest.c | 2 +- .../deck/drivers/src/test/aidecktest.c | 10 +- .../deck/drivers/src/zranger2.c | 2 +- .../drivers/bosch/src/bstdr_comm_support.c | 2 +- .../drivers/src/eeprom.c | 4 +- .../drivers/src/nvic.c | 2 +- .../hal/src/amg8833.c | 2 +- .../hal/src/ledseq.c | 2 +- .../hal/src/ow_syslink.c | 28 +- .../hal/src/radiolink.c | 19 +- .../hal/src/sensors_bmi088_bmp388.c | 6 +- .../hal/src/sensors_bosch.c | 4 +- .../hal/src/sensors_mpu9250_lps25h.c | 2 +- .../hal/src/usb.c | 203 ++--- .../hal/src/usbd_desc.c | 65 +- .../hal/src/usblink.c | 14 +- .../modules/interface/math3d.h | 2 +- .../modules/src/app_handler.c | 2 +- .../modules/src/collision_avoidance.c | 124 +-- .../modules/src/commander.c | 123 +-- .../modules/src/controller_pid.c | 2 +- .../modules/src/crtp.c | 247 +++--- .../modules/src/crtp_commander_high_level.c | 808 +++++++++--------- .../modules/src/crtp_commander_rpyt.c | 2 +- .../modules/src/crtp_localization_service.c | 410 ++++----- .../modules/src/crtpservice.c | 2 +- .../modules/src/log.c | 12 +- .../modules/src/position_controller_indi.c | 2 +- .../modules/src/position_controller_pid.c | 2 +- .../modules/src/stabilizer.c | 304 +++---- .../modules/src/system.c | 38 +- .../uart/build/amg8833.o | Bin 4144 -> 4024 bytes .../uart/build/app_handler.o | Bin 2496 -> 2240 bytes .../uart/build/bstdr_comm_support.o | Bin 1736 -> 1600 bytes .../uart/build/collision_avoidance.o | Bin 4632 -> 3032 bytes .../uart/build/commander.o | Bin 6984 -> 2128 bytes .../uart/build/controller_pid.o | Bin 5832 -> 5960 bytes .../uart/build/crtp.o | Bin 13384 -> 2368 bytes .../uart/build/crtp_commander_high_level.o | Bin 11008 -> 3288 bytes .../uart/build/crtp_commander_rpyt.o | Bin 3968 -> 3848 bytes .../uart/build/crtp_localization_service.o | Bin 8784 -> 4192 bytes .../uart/build/crtpservice.o | Bin 4760 -> 4616 bytes .../uart/build/eeprom.o | Bin 3896 -> 3704 bytes .../uart/build/ledseq.o | Bin 5888 -> 5776 bytes .../uart/build/log.o | Bin 23976 -> 23144 bytes .../uart/build/nvic.o | Bin 1528 -> 1392 bytes .../uart/build/ow_syslink.o | Bin 5616 -> 5184 bytes .../uart/build/position_controller_indi.o | Bin 11560 -> 11528 bytes .../uart/build/position_controller_pid.o | Bin 9488 -> 9440 bytes .../uart/build/pulse_processor_v2.o | Bin 3408 -> 1176 bytes .../uart/build/radiolink.o | Bin 8320 -> 7960 bytes .../uart/build/stabilizer.o | Bin 12984 -> 11536 bytes .../uart/build/system.o | Bin 11904 -> 11728 bytes .../uart/build/usb.o | Bin 9368 -> 6176 bytes .../uart/build/usbd_desc.o | Bin 3704 -> 2296 bytes .../uart/build/usblink.o | Bin 4944 -> 2976 bytes .../utils/src/lighthouse/pulse_processor_v2.c | 420 ++++----- .../FreeRTOS/Source/include/queue.h | 2 +- .../bm_crazyflie/FreeRTOS/Source/timers.c | 2 +- 60 files changed, 1462 insertions(+), 1410 deletions(-) diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/config/FreeRTOSConfig.h b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/config/FreeRTOSConfig.h index ad9af7c29..6432827ab 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/config/FreeRTOSConfig.h +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/config/FreeRTOSConfig.h @@ -39,7 +39,6 @@ by writing to Richard Barry, contact details for whom are available on the FreeRTOS WEB site. - 1 tab == 4 spaces! http://www.FreeRTOS.org - Documentation, latest information, license and contact details. diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/test/activeMarkerUartTest.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/test/activeMarkerUartTest.c index 0f94ec365..0e4a90b26 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/test/activeMarkerUartTest.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/test/activeMarkerUartTest.c @@ -67,7 +67,7 @@ static void task(void *param) } } - vTaskDelay(M2T(100)); + //vTaskDelay(M2T(100)); } } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/test/aidecktest.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/test/aidecktest.c index 0103bb869..9de7b78c3 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/test/aidecktest.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/test/aidecktest.c @@ -233,7 +233,7 @@ static bool aitdecktestTest() pinMode(DECK_GPIO_IO4, INPUT_PULLUP); // Wait for the NINA to start - vTaskDelay(M2T(1000)); + // vTaskDelay(M2T(1000)); // Empty the buffer from NINA while (uart2GetDataWithDefaultTimeout(&byte) == true) ; @@ -250,7 +250,7 @@ static bool aitdecktestTest() testHasBeenTriggered = true; } - vTaskDelay(M2T(100)); + // vTaskDelay(M2T(100)); } // Send test for button high NINA @@ -297,7 +297,7 @@ static bool aitdecktestTest() if (testOnGAP8(GAP8_GPIO_COMMAND|GAP8_GPIO_MASK, GAP8_GPIO_MASK_EXPECTED) == true) { - vTaskDelay(M2T(100)); + // vTaskDelay(M2T(100)); // Send test for GPIO mask to NINA if (testOnNinaMask(NINA_GAP8_GPIO_COMMAND, &gpio_mask) == true) { @@ -317,7 +317,7 @@ static bool aitdecktestTest() { DEBUG_PRINT("Set GAP8 gpio mask [FAILED]\r\n"); } - vTaskDelay(M2T(100)); + // vTaskDelay(M2T(100)); uint8_t not_mask = (~GAP8_GPIO_MASK) & 0X3F; @@ -325,7 +325,7 @@ static bool aitdecktestTest() // Send test for ~ GPIO mask to GAP8 if (testOnGAP8(GAP8_GPIO_COMMAND | not_mask, GAP8_GPIO_MASK_EXPECTED) == true) { - vTaskDelay(M2T(100)); + // vTaskDelay(M2T(100)); // Send test for ~ GPIO mask to NINA if (testOnNinaMask(NINA_GAP8_GPIO_COMMAND, &gpio_mask) == true) { diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/zranger2.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/zranger2.c index 014ba745b..71767e100 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/zranger2.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/zranger2.c @@ -69,7 +69,7 @@ static uint16_t zRanger2GetMeasurementAndRestart(VL53L1_Dev_t *dev) while (dataReady == 0) { status = VL53L1_GetMeasurementDataReady(dev, &dataReady); - vTaskDelay(M2T(1)); + // vTaskDelay(M2T(1)); } status = VL53L1_GetRangingMeasurementData(dev, &rangingData); diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/drivers/bosch/src/bstdr_comm_support.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/drivers/bosch/src/bstdr_comm_support.c index eb5519a7c..3b40d4393 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/drivers/bosch/src/bstdr_comm_support.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/drivers/bosch/src/bstdr_comm_support.c @@ -158,6 +158,6 @@ bstdr_ret_t bstdr_burst_write(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_dat void bstdr_ms_delay(uint32_t period) { /**< Delay code comes */ - vTaskDelay(M2T(period)); // Delay a while to let the device stabilize + // vTaskDelay(M2T(period)); // Delay a while to let the device stabilize } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/drivers/src/eeprom.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/drivers/src/eeprom.c index 422e688eb..c76177aa7 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/drivers/src/eeprom.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/drivers/src/eeprom.c @@ -181,7 +181,7 @@ bool eepromWriteBuffer(const uint8_t* buffer, uint16_t writeAddr, uint16_t len) if (status) { break; } - vTaskDelay(M2T(6)); + //vTaskDelay(M2T(6)); } if (!status) { return false; @@ -196,7 +196,7 @@ bool eepromWriteBuffer(const uint8_t* buffer, uint16_t writeAddr, uint16_t len) break; } - vTaskDelay(M2T(1)); + // vTaskDelay(M2T(1)); } if (!status) { return false; diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/drivers/src/nvic.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/drivers/src/nvic.c index 9cc83b178..3aca5d570 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/drivers/src/nvic.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/drivers/src/nvic.c @@ -47,7 +47,7 @@ extern void tickFreeRTOS(void); void DONT_DISCARD SysTick_Handler(void) { - tickFreeRTOS(); + // tickFreeRTOS(); } #ifdef NVIC_NOT_USED_BY_FREERTOS diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/amg8833.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/amg8833.c index 97f1f778e..ab7e4949c 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/amg8833.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/amg8833.c @@ -51,7 +51,7 @@ bool begin(AMG8833_Dev_t *dev, I2C_Dev *I2Cx) bool interrupts_set = disableInterrupt(dev); //set to 10 FPS bool fps_set = write8(dev, AMG88xx_FPSC, (AMG88xx_FPS_10 & 0x01)); - vTaskDelay(M2T(10)); + //vTaskDelay(M2T(10)); return mode_selected && software_resetted && interrupts_set && fps_set; } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/ledseq.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/ledseq.c index ff5cd881a..b6a387056 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/ledseq.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/ledseq.c @@ -356,7 +356,7 @@ static void runLedseq( xTimerHandle xTimer ) { if (step->action == 0) { break; } - xTimerChangePeriod(xTimer, M2T(step->action), 0); + // xTimerChangePeriod(xTimer, M2T(step->action), 0); xTimerStart(xTimer, 0); leave = true; break; diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/ow_syslink.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/ow_syslink.c index b858b5f9a..a3224d02e 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/ow_syslink.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/ow_syslink.c @@ -154,20 +154,20 @@ static bool owSyslinkTransfer(uint8_t type, uint8_t length) syslinkSendPacket(&slp); // Wait for reply - if (xSemaphoreTake(waitForReply, M2T(5000)) == pdTRUE) - //if (xSemaphoreTake(waitForReply, portMAX_DELAY)) - { - // We have now got a reply and *owCmd has been filled with data - if (owDataIsValid) - { - owDataIsValid = false; - return true; - } - } - else - { - DEBUG_PRINT("Cmd 0x%X timeout.\n", slp.type); - } + // if (xSemaphoreTake(waitForReply, M2T(5000)) == pdTRUE) + // //if (xSemaphoreTake(waitForReply, portMAX_DELAY)) + // { + // // We have now got a reply and *owCmd has been filled with data + // if (owDataIsValid) + // { + // owDataIsValid = false; + // return true; + // } + // } + // else + // { + // DEBUG_PRINT("Cmd 0x%X timeout.\n", slp.type); + // } return false; } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/radiolink.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/radiolink.c index 738901f33..b94ddc26f 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/radiolink.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/radiolink.c @@ -71,7 +71,8 @@ static uint32_t lastPacketTick; static volatile P2PCallback p2p_callback; static bool radiolinkIsConnected(void) { - return (xTaskGetTickCount() - lastPacketTick) < M2T(RADIO_ACTIVITY_TIMEOUT_MS); + //return (xTaskGetTickCount() - lastPacketTick) < M2T(RADIO_ACTIVITY_TIMEOUT_MS); + return true; } static struct crtpLinkOperations radiolinkOp = @@ -197,10 +198,10 @@ void radiolinkSyslinkDispatch(SyslinkPacket *slp) static int radiolinkReceiveCRTPPacket(CRTPPacket *p) { - if (xQueueReceive(crtpPacketDelivery, p, M2T(100)) == pdTRUE) - { - return 0; - } + // if (xQueueReceive(crtpPacketDelivery, p, M2T(100)) == pdTRUE) + // { + // return 0; + // } return -1; } @@ -220,10 +221,10 @@ static int radiolinkSendCRTPPacket(CRTPPacket *p) slp.length = p->size + 1; memcpy(slp.data, &p->header, p->size + 1); - if (xQueueSend(txQueue, &slp, M2T(100)) == pdTRUE) - { - return true; - } + // if (xQueueSend(txQueue, &slp, M2T(100)) == pdTRUE) + // { + // return true; + // } return false; } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/sensors_bmi088_bmp388.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/sensors_bmi088_bmp388.c index 0ecc3fd33..7cb36b755 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/sensors_bmi088_bmp388.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/sensors_bmi088_bmp388.c @@ -27,7 +27,7 @@ #define DEBUG_MODULE "IMU" #include <math.h> -#include "empty_math.h" +// #include "empty_math.h" #include "sensors_bmi088_bmp388.h" #include "stm32fxxx.h" @@ -219,7 +219,7 @@ bstdr_ret_t bmi088_burst_write(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_da void bmi088_ms_delay(uint32_t period) { /**< Delay code comes */ - vTaskDelay(M2T(period)); // Delay a while to let the device stabilize + // vTaskDelay(M2T(period)); // Delay a while to let the device stabilize } static uint16_t sensorsGyroGet(Axis3i16* dataOut) @@ -372,7 +372,7 @@ static void sensorsDeviceInit(void) isBarometerPresent = false; // Wait for sensors to startup - vTaskDelay(M2T(SENSORS_STARTUP_TIME_MS)); + // vTaskDelay(M2T(SENSORS_STARTUP_TIME_MS)); /* BMI088 * The bmi088Dev structure should have been filled in by the backend diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/sensors_bosch.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/sensors_bosch.c index 85adbf7be..2607081ae 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/sensors_bosch.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/sensors_bosch.c @@ -34,7 +34,7 @@ #include "sensors_bosch.h" #include <math.h> -#include "empty_math.h" +// #include "empty_math.h" #include "stm32fxxx.h" @@ -230,7 +230,7 @@ static void sensorsDeviceInit(void) isBarometerPresent = false; // Wait for sensors to startup - vTaskDelay(M2T(SENSORS_STARTUP_TIME_MS)); + // vTaskDelay(M2T(SENSORS_STARTUP_TIME_MS)); /* BMI160 */ // assign bus read function diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/sensors_mpu9250_lps25h.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/sensors_mpu9250_lps25h.c index 3b441215d..5fa7a0b6c 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/sensors_mpu9250_lps25h.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/sensors_mpu9250_lps25h.c @@ -29,7 +29,7 @@ #include "sensors_mpu9250_lps25h.h" #include <math.h> -#include "empty_math.h" +// #include "empty_math.h" #include <stm32f4xx.h> #include "lps25h.h" diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/usb.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/usb.c index 1f300a9b3..6d649462b 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/usb.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/usb.c @@ -160,7 +160,7 @@ static void resetUSB(void) { ; } - USB_OTG_FlushTxFifo(&USB_OTG_dev, IN_EP); + //USB_OTG_FlushTxFifo(&USB_OTG_dev, IN_EP); rxStopped = true; doingTransfer = false; @@ -168,48 +168,48 @@ static void resetUSB(void) { static uint8_t usbd_cf_Setup(void *pdev , USB_SETUP_REQ *req) { - command = req->wIndex; - if (command == 0x01) { - crtpSetLink(usblinkGetLink()); - - if (rxStopped && !xQueueIsQueueFullFromISR(usbDataRx)) { - DCD_EP_PrepareRx(&USB_OTG_dev, - OUT_EP, - (uint8_t*)(inPacket.data), - USB_RX_TX_PACKET_SIZE); - rxStopped = false; - } - } else if(command == 0x02){ - //restart system and transition to DFU bootloader mode - //enter bootloader specific to STM32f4xx - enter_bootloader(0, 0x00000000); - } else { - crtpSetLink(radiolinkGetLink()); - } + // command = req->wIndex; + // if (command == 0x01) { + // crtpSetLink(usblinkGetLink()); + + // if (rxStopped && !xQueueIsQueueFullFromISR(usbDataRx)) { + // DCD_EP_PrepareRx(&USB_OTG_dev, + // OUT_EP, + // (uint8_t*)(inPacket.data), + // USB_RX_TX_PACKET_SIZE); + // rxStopped = false; + // } + // } else if(command == 0x02){ + // //restart system and transition to DFU bootloader mode + // //enter bootloader specific to STM32f4xx + // enter_bootloader(0, 0x00000000); + // } else { + // crtpSetLink(radiolinkGetLink()); + // } return USBD_OK; } static uint8_t usbd_cf_Init (void *pdev, uint8_t cfgidx) { - /* Open EP IN */ - DCD_EP_Open(pdev, - IN_EP, - USB_RX_TX_PACKET_SIZE, - USB_OTG_EP_BULK); - - /* Open EP OUT */ - DCD_EP_Open(pdev, - OUT_EP, - USB_RX_TX_PACKET_SIZE, - USB_OTG_EP_BULK); - - /* Prepare Out endpoint to receive next packet */ - DCD_EP_PrepareRx(pdev, - OUT_EP, - (uint8_t*)(inPacket.data), - USB_RX_TX_PACKET_SIZE); - rxStopped = false; + // /* Open EP IN */ + // DCD_EP_Open(pdev, + // IN_EP, + // USB_RX_TX_PACKET_SIZE, + // USB_OTG_EP_BULK); + + // /* Open EP OUT */ + // DCD_EP_Open(pdev, + // OUT_EP, + // USB_RX_TX_PACKET_SIZE, + // USB_OTG_EP_BULK); + + // /* Prepare Out endpoint to receive next packet */ + // DCD_EP_PrepareRx(pdev, + // OUT_EP, + // (uint8_t*)(inPacket.data), + // USB_RX_TX_PACKET_SIZE); + // rxStopped = false; return USBD_OK; } @@ -224,11 +224,11 @@ static uint8_t usbd_cf_Init (void *pdev, static uint8_t usbd_cf_DeInit (void *pdev, uint8_t cfgidx) { - /* Open EP IN */ - DCD_EP_Close(pdev, IN_EP); + // /* Open EP IN */ + // DCD_EP_Close(pdev, IN_EP); - /* Open EP OUT */ - DCD_EP_Close(pdev, OUT_EP); + // /* Open EP OUT */ + // DCD_EP_Close(pdev, OUT_EP); return USBD_OK; } @@ -242,40 +242,40 @@ static uint8_t usbd_cf_DeInit (void *pdev, */ static uint8_t usbd_cf_DataIn (void *pdev, uint8_t epnum) { - portBASE_TYPE xTaskWokenByReceive = pdFALSE; + // portBASE_TYPE xTaskWokenByReceive = pdFALSE; - doingTransfer = false; + // doingTransfer = false; - if (xQueueReceiveFromISR(usbDataTx, &outPacket, &xTaskWokenByReceive) == pdTRUE) - { - doingTransfer = true; - DCD_EP_Tx (pdev, - IN_EP, - (uint8_t*)outPacket.data, - outPacket.size); - } + // if (xQueueReceiveFromISR(usbDataTx, &outPacket, &xTaskWokenByReceive) == pdTRUE) + // { + // doingTransfer = true; + // DCD_EP_Tx (pdev, + // IN_EP, + // (uint8_t*)outPacket.data, + // outPacket.size); + // } - portYIELD_FROM_ISR(xTaskWokenByReceive); + // portYIELD_FROM_ISR(xTaskWokenByReceive); return USBD_OK; } static uint8_t usbd_cf_SOF (void *pdev) { - portBASE_TYPE xTaskWokenByReceive = pdFALSE; + // portBASE_TYPE xTaskWokenByReceive = pdFALSE; - if (!doingTransfer) { - if (xQueueReceiveFromISR(usbDataTx, &outPacket, &xTaskWokenByReceive) == pdTRUE) - { - doingTransfer = true; - DCD_EP_Tx (pdev, - IN_EP, - (uint8_t*)outPacket.data, - outPacket.size); - } - } + // if (!doingTransfer) { + // if (xQueueReceiveFromISR(usbDataTx, &outPacket, &xTaskWokenByReceive) == pdTRUE) + // { + // doingTransfer = true; + // DCD_EP_Tx (pdev, + // IN_EP, + // (uint8_t*)outPacket.data, + // outPacket.size); + // } + // } - portYIELD_FROM_ISR(xTaskWokenByReceive); + // portYIELD_FROM_ISR(xTaskWokenByReceive); return USBD_OK; } @@ -289,28 +289,28 @@ static uint8_t usbd_cf_SOF (void *pdev) */ static uint8_t usbd_cf_DataOut (void *pdev, uint8_t epnum) { - uint8_t result; - portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; - - /* Get the received data buffer and update the counter */ - inPacket.size = ((USB_OTG_CORE_HANDLE*)pdev)->dev.out_ep[epnum].xfer_count; - - if (xQueueSendFromISR(usbDataRx, &inPacket, &xHigherPriorityTaskWoken) == pdTRUE) { - result = USBD_OK; - } else { - result = USBD_BUSY; - } - - if (!xQueueIsQueueFullFromISR(usbDataRx)) { - /* Prepare Out endpoint to receive next packet */ - DCD_EP_PrepareRx(pdev, - OUT_EP, - (uint8_t*)(inPacket.data), - USB_RX_TX_PACKET_SIZE); - rxStopped = false; - } else { - rxStopped = true; - } + uint8_t result = USBD_OK; + // portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + + // /* Get the received data buffer and update the counter */ + // inPacket.size = ((USB_OTG_CORE_HANDLE*)pdev)->dev.out_ep[epnum].xfer_count; + + // if (xQueueSendFromISR(usbDataRx, &inPacket, &xHigherPriorityTaskWoken) == pdTRUE) { + // result = USBD_OK; + // } else { + // result = USBD_BUSY; + // } + + // if (!xQueueIsQueueFullFromISR(usbDataRx)) { + // /* Prepare Out endpoint to receive next packet */ + // DCD_EP_PrepareRx(pdev, + // OUT_EP, + // (uint8_t*)(inPacket.data), + // USB_RX_TX_PACKET_SIZE); + // rxStopped = false; + // } else { + // rxStopped = true; + // } return result; } @@ -424,20 +424,20 @@ bool usbTest(void) bool usbGetDataBlocking(USBPacket *in) { - while (xQueueReceive(usbDataRx, in, portMAX_DELAY) != pdTRUE) - ; // Don't return until we get some data on the USB - - // Disabling USB interrupt to make sure we can check and re-enable the endpoint - // if it is not currently accepting data (ie. can happen if the RX queue was full) - NVIC_DisableIRQ(OTG_FS_IRQn); - if (rxStopped) { - DCD_EP_PrepareRx(&USB_OTG_dev, - OUT_EP, - (uint8_t*)(inPacket.data), - USB_RX_TX_PACKET_SIZE); - rxStopped = false; - } - NVIC_EnableIRQ(OTG_FS_IRQn); + // while (xQueueReceive(usbDataRx, in, portMAX_DELAY) != pdTRUE) + // ; // Don't return until we get some data on the USB + + // // Disabling USB interrupt to make sure we can check and re-enable the endpoint + // // if it is not currently accepting data (ie. can happen if the RX queue was full) + // NVIC_DisableIRQ(OTG_FS_IRQn); + // if (rxStopped) { + // DCD_EP_PrepareRx(&USB_OTG_dev, + // OUT_EP, + // (uint8_t*)(inPacket.data), + // USB_RX_TX_PACKET_SIZE); + // rxStopped = false; + // } + // NVIC_EnableIRQ(OTG_FS_IRQn); return true; } @@ -449,5 +449,6 @@ bool usbSendData(uint32_t size, uint8_t* data) outStage.size = size; memcpy(outStage.data, data, size); // Dont' block when sending - return (xQueueSend(usbDataTx, &outStage, M2T(100)) == pdTRUE); + //return (xQueueSend(usbDataTx, &outStage, M2T(100)) == pdTRUE); + return true; } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/usbd_desc.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/usbd_desc.c index 42e681c5d..66599f35f 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/usbd_desc.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/usbd_desc.c @@ -221,15 +221,16 @@ uint8_t * USBD_USR_ProductStrDescriptor( uint8_t speed , uint16_t *length) { - if(speed == 0) - { - USBD_GetString ((uint8_t *)USBD_PRODUCT_HS_STRING, USBD_StrDesc, length); - } - else - { - USBD_GetString ((uint8_t *)USBD_PRODUCT_FS_STRING, USBD_StrDesc, length); - } - return USBD_StrDesc; + // if(speed == 0) + // { + // USBD_GetString ((uint8_t *)USBD_PRODUCT_HS_STRING, USBD_StrDesc, length); + // } + // else + // { + // USBD_GetString ((uint8_t *)USBD_PRODUCT_FS_STRING, USBD_StrDesc, length); + // } + // return USBD_StrDesc; + return 0; } /** @@ -241,8 +242,9 @@ uint8_t * USBD_USR_ProductStrDescriptor( uint8_t speed , uint16_t *length) */ uint8_t * USBD_USR_ManufacturerStrDescriptor( uint8_t speed , uint16_t *length) { - USBD_GetString ((uint8_t *)USBD_MANUFACTURER_STRING, USBD_StrDesc, length); - return USBD_StrDesc; + //USBD_GetString ((uint8_t *)USBD_MANUFACTURER_STRING, USBD_StrDesc, length); + //return USBD_StrDesc; + return 0; } static const char bin2hex[] = {'0', '1', '2', '3', '4', '5', '6', '7', @@ -272,7 +274,8 @@ uint8_t * USBD_USR_SerialStrDescriptor( uint8_t speed , uint16_t *length) // USBD_GetString ((uint8_t *)serial_nr, USBD_StrDesc, length); - return USBD_StrDesc; + //return USBD_StrDesc; + return 0; } /** @@ -284,15 +287,16 @@ uint8_t * USBD_USR_SerialStrDescriptor( uint8_t speed , uint16_t *length) */ uint8_t * USBD_USR_ConfigStrDescriptor( uint8_t speed , uint16_t *length) { - if(speed == USB_OTG_SPEED_HIGH) - { - USBD_GetString ((uint8_t *)USBD_CONFIGURATION_HS_STRING, USBD_StrDesc, length); - } - else - { - USBD_GetString ((uint8_t *)USBD_CONFIGURATION_FS_STRING, USBD_StrDesc, length); - } - return USBD_StrDesc; + // if(speed == USB_OTG_SPEED_HIGH) + // { + // USBD_GetString ((uint8_t *)USBD_CONFIGURATION_HS_STRING, USBD_StrDesc, length); + // } + // else + // { + // USBD_GetString ((uint8_t *)USBD_CONFIGURATION_FS_STRING, USBD_StrDesc, length); + // } + // return USBD_StrDesc; + return 0; } @@ -305,15 +309,16 @@ uint8_t * USBD_USR_ConfigStrDescriptor( uint8_t speed , uint16_t *length) */ uint8_t * USBD_USR_InterfaceStrDescriptor( uint8_t speed , uint16_t *length) { - if(speed == 0) - { - USBD_GetString ((uint8_t *)USBD_INTERFACE_HS_STRING, USBD_StrDesc, length); - } - else - { - USBD_GetString ((uint8_t *)USBD_INTERFACE_FS_STRING, USBD_StrDesc, length); - } - return USBD_StrDesc; + // if(speed == 0) + // { + // USBD_GetString ((uint8_t *)USBD_INTERFACE_HS_STRING, USBD_StrDesc, length); + // } + // else + // { + // USBD_GetString ((uint8_t *)USBD_INTERFACE_FS_STRING, USBD_StrDesc, length); + // } + // return USBD_StrDesc; + return 0; } /** diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/usblink.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/usblink.c index 225edc6ad..fb1834867 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/usblink.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/hal/src/usblink.c @@ -84,11 +84,11 @@ static void usblinkTask(void *param) static int usblinkReceivePacket(CRTPPacket *p) { - if (xQueueReceive(crtpPacketDelivery, p, M2T(100)) == pdTRUE) - { - ledseqRun(&seq_linkUp); - return 0; - } + // if (xQueueReceive(crtpPacketDelivery, p, M2T(100)) == pdTRUE) + // { + // ledseqRun(&seq_linkUp); + // return 0; + // } return -1; } @@ -130,10 +130,10 @@ void usblinkInit() // Initialize the USB peripheral usbInit(); - crtpPacketDelivery = STATIC_MEM_QUEUE_CREATE(crtpPacketDelivery); + //crtpPacketDelivery = STATIC_MEM_QUEUE_CREATE(crtpPacketDelivery); DEBUG_QUEUE_MONITOR_REGISTER(crtpPacketDelivery); - STATIC_MEM_TASK_CREATE(usblinkTask, usblinkTask, USBLINK_TASK_NAME, NULL, USBLINK_TASK_PRI); + //STATIC_MEM_TASK_CREATE(usblinkTask, usblinkTask, USBLINK_TASK_NAME, NULL, USBLINK_TASK_PRI); isInit = true; } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/interface/math3d.h b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/interface/math3d.h index c3adb7681..3962908df 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/interface/math3d.h +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/interface/math3d.h @@ -26,7 +26,7 @@ SOFTWARE. */ #include <math.h> -#include "empty_math.h" +// #include "empty_math.h" #include <stdbool.h> #include <stddef.h> diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/app_handler.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/app_handler.c index 389402ecf..aae3053eb 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/app_handler.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/app_handler.c @@ -33,7 +33,7 @@ #include "static_mem.h" #include "app.h" -#include "empty_math.h" +// #include "empty_math.h" #ifndef APP_STACKSIZE #define APP_STACKSIZE 300 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/collision_avoidance.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/collision_avoidance.c index d618e5198..391e9a184 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/collision_avoidance.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/collision_avoidance.c @@ -40,12 +40,12 @@ // math operations. static struct vec vec2svec(struct vec3_s v) { - return mkvec(v.x, v.y, v.z); + // return mkvec(v.x, v.y, v.z); } static struct vec3_s svec2vec(struct vec v) { - struct vec3_s vv = { .x = v.x, .y = v.y, .z = v.z, }; - return vv; + // struct vec3_s vv = { .x = v.x, .y = v.y, .z = v.z, }; + // return vv; } // Computes a new goal position inside our buffered Voronoi cell. @@ -74,24 +74,24 @@ static struct vec sidestepGoal( bool modifyIfInside, float const A[], float const B[], float projectionWorkspace[], int nRows) { - float const rayScale = rayintersectpolytope(vzero(), goal, A, B, nRows, NULL); - if (rayScale >= 1.0f && !modifyIfInside) { - return goal; - } - float const distance = vmag(goal); - float const distFromWall = rayScale * distance; - if (distFromWall <= params->sidestepThreshold) { - struct vec sidestepDir = vcross(goal, mkvec(0.0f, 0.0f, 1.0f)); - float const sidestepAmount = fsqr(1.0f - distFromWall / params->sidestepThreshold); - goal = vadd(goal, vscl(sidestepAmount, sidestepDir)); - } - // Otherwise no sidestep, but still project - return vprojectpolytope( - goal, - A, B, projectionWorkspace, nRows, - params->voronoiProjectionTolerance, - params->voronoiProjectionMaxIters - ); + // float const rayScale = rayintersectpolytope(vzero(), goal, A, B, nRows, NULL); + // if (rayScale >= 1.0f && !modifyIfInside) { + // return goal; + // } + // float const distance = vmag(goal); + // float const distFromWall = rayScale * distance; + // if (distFromWall <= params->sidestepThreshold) { + // struct vec sidestepDir = vcross(goal, mkvec(0.0f, 0.0f, 1.0f)); + // float const sidestepAmount = fsqr(1.0f - distFromWall / params->sidestepThreshold); + // goal = vadd(goal, vscl(sidestepAmount, sidestepDir)); + // } + // // Otherwise no sidestep, but still project + // return vprojectpolytope( + // goal, + // A, B, projectionWorkspace, nRows, + // params->voronoiProjectionTolerance, + // params->voronoiProjectionMaxIters + // ); } void collisionAvoidanceUpdateSetpointCore( @@ -269,22 +269,22 @@ void collisionAvoidanceUpdateSetpointCore( #include "log.h" -static uint8_t collisionAvoidanceEnable = 0; +// static uint8_t collisionAvoidanceEnable = 0; static collision_avoidance_params_t params = { - .ellipsoidRadii = { .x = 0.3, .y = 0.3, .z = 0.9 }, - .bboxMin = { .x = -FLT_MAX, .y = -FLT_MAX, .z = -FLT_MAX }, - .bboxMax = { .x = FLT_MAX, .y = FLT_MAX, .z = FLT_MAX }, - .horizonSecs = 1.0f, - .maxSpeed = 0.5f, // Fairly conservative. - .sidestepThreshold = 0.25f, - .maxPeerLocAgeMillis = 5000, // Probably longer than desired in most applications. - .voronoiProjectionTolerance = 1e-5, - .voronoiProjectionMaxIters = 100, + // .ellipsoidRadii = { .x = 0.3, .y = 0.3, .z = 0.9 }, + // .bboxMin = { .x = -FLT_MAX, .y = -FLT_MAX, .z = -FLT_MAX }, + // .bboxMax = { .x = FLT_MAX, .y = FLT_MAX, .z = FLT_MAX }, + // .horizonSecs = 1.0f, + // .maxSpeed = 0.5f, // Fairly conservative. + // .sidestepThreshold = 0.25f, + // .maxPeerLocAgeMillis = 5000, // Probably longer than desired in most applications. + // .voronoiProjectionTolerance = 1e-5, + // .voronoiProjectionMaxIters = 100, }; static collision_avoidance_state_t collisionState = { - .lastFeasibleSetPosition = { .x = NAN, .y = NAN, .z = NAN }, + // .lastFeasibleSetPosition = { .x = NAN, .y = NAN, .z = NAN }, }; void collisionAvoidanceInit() @@ -293,58 +293,58 @@ void collisionAvoidanceInit() bool collisionAvoidanceTest() { - return true; + // return true; } // Each face of the Voronoi cell is defined by a linear inequality a^T x <= b. // The algorithm for projecting a point into a convex polytope requires 3 more // floats of working space per face. The six extra faces come from the overall // flight area bounding box. -#define MAX_CELL_ROWS (PEER_LOCALIZATION_MAX_NEIGHBORS + 6) -static float workspace[7 * MAX_CELL_ROWS]; +// #define MAX_CELL_ROWS (PEER_LOCALIZATION_MAX_NEIGHBORS + 6) +// static float workspace[7 * MAX_CELL_ROWS]; // Latency counter for logging. -static uint32_t latency = 0; +// static uint32_t latency = 0; void collisionAvoidanceUpdateSetpoint( setpoint_t *setpoint, sensorData_t const *sensorData, state_t const *state, uint32_t tick) { - if (!collisionAvoidanceEnable) { - return; - } + // if (!collisionAvoidanceEnable) { + // return; + // } - TickType_t const time = xTaskGetTickCount(); - bool doAgeFilter = params.maxPeerLocAgeMillis >= 0; + // TickType_t const time = xTaskGetTickCount(); + // bool doAgeFilter = params.maxPeerLocAgeMillis >= 0; - // Counts the actual number of neighbors after we filter stale measurements. - int nOthers = 0; + // // Counts the actual number of neighbors after we filter stale measurements. + // int nOthers = 0; - for (int i = 0; i < PEER_LOCALIZATION_MAX_NEIGHBORS; ++i) { + // for (int i = 0; i < PEER_LOCALIZATION_MAX_NEIGHBORS; ++i) { - peerLocalizationOtherPosition_t const *otherPos = peerLocalizationGetPositionByIdx(i); + // peerLocalizationOtherPosition_t const *otherPos = peerLocalizationGetPositionByIdx(i); - if (otherPos == NULL || otherPos->id == 0) { - continue; - } + // if (otherPos == NULL || otherPos->id == 0) { + // continue; + // } - if (doAgeFilter && (time - otherPos->pos.timestamp > params.maxPeerLocAgeMillis)) { - continue; - } + // if (doAgeFilter && (time - otherPos->pos.timestamp > params.maxPeerLocAgeMillis)) { + // continue; + // } - workspace[3 * nOthers + 0] = otherPos->pos.x; - workspace[3 * nOthers + 1] = otherPos->pos.y; - workspace[3 * nOthers + 2] = otherPos->pos.z; - ++nOthers; - } + // workspace[3 * nOthers + 0] = otherPos->pos.x; + // workspace[3 * nOthers + 1] = otherPos->pos.y; + // workspace[3 * nOthers + 2] = otherPos->pos.z; + // ++nOthers; + // } - collisionAvoidanceUpdateSetpointCore(¶ms, &collisionState, nOthers, workspace, workspace, setpoint, sensorData, state); + // collisionAvoidanceUpdateSetpointCore(¶ms, &collisionState, nOthers, workspace, workspace, setpoint, sensorData, state); - latency = xTaskGetTickCount() - time; + // latency = xTaskGetTickCount() - time; } -LOG_GROUP_START(colAv) - LOG_ADD(LOG_UINT32, latency, &latency) -LOG_GROUP_STOP(colAv) +// LOG_GROUP_START(colAv) +// LOG_ADD(LOG_UINT32, latency, &latency) +// LOG_GROUP_STOP(colAv) /** @@ -396,7 +396,7 @@ PARAM_GROUP_START(colAv) * * Used to enable or disable the collision avoidance module. */ - PARAM_ADD_CORE(PARAM_UINT8, enable, &collisionAvoidanceEnable) + //PARAM_ADD_CORE(PARAM_UINT8, enable, &collisionAvoidanceEnable) /** * @brief The x radius of the ellipsoid collision volume diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/commander.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/commander.c index 49fb2dcb6..4cd861d18 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/commander.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/commander.c @@ -55,37 +55,41 @@ STATIC_MEM_QUEUE_ALLOC(priorityQueue, 1, sizeof(int)); /* Public functions */ void commanderInit(void) { - setpointQueue = STATIC_MEM_QUEUE_CREATE(setpointQueue); - ASSERT(setpointQueue); - xQueueSend(setpointQueue, &nullSetpoint, 0); + //COMMENTED FIRMWARE + + // setpointQueue = STATIC_MEM_QUEUE_CREATE(setpointQueue); + // ASSERT(setpointQueue); + // xQueueSend(setpointQueue, &nullSetpoint, 0); - priorityQueue = STATIC_MEM_QUEUE_CREATE(priorityQueue); - ASSERT(priorityQueue); - xQueueSend(priorityQueue, &priorityDisable, 0); + // priorityQueue = STATIC_MEM_QUEUE_CREATE(priorityQueue); + // ASSERT(priorityQueue); + // xQueueSend(priorityQueue, &priorityDisable, 0); - crtpCommanderInit(); - crtpCommanderHighLevelInit(); - lastUpdate = xTaskGetTickCount(); + // crtpCommanderInit(); + // crtpCommanderHighLevelInit(); + // lastUpdate = xTaskGetTickCount(); - isInit = true; + // isInit = true; } void commanderSetSetpoint(setpoint_t *setpoint, int priority) { - int currentPriority; - - const BaseType_t peekResult = xQueuePeek(priorityQueue, ¤tPriority, 0); - ASSERT(peekResult == pdTRUE); - - if (priority >= currentPriority) { - setpoint->timestamp = xTaskGetTickCount(); - // This is a potential race but without effect on functionality - xQueueOverwrite(setpointQueue, setpoint); - xQueueOverwrite(priorityQueue, &priority); - // Send the high-level planner to idle so it will forget its current state - // and start over if we switch from low-level to high-level in the future. - crtpCommanderHighLevelStop(); - } + //COMMENTED FIRMWARE + + // int currentPriority; + + // const BaseType_t peekResult = xQueuePeek(priorityQueue, ¤tPriority, 0); + // ASSERT(peekResult == pdTRUE); + + // if (priority >= currentPriority) { + // setpoint->timestamp = xTaskGetTickCount(); + // // This is a potential race but without effect on functionality + // xQueueOverwrite(setpointQueue, setpoint); + // xQueueOverwrite(priorityQueue, &priority); + // // Send the high-level planner to idle so it will forget its current state + // // and start over if we switch from low-level to high-level in the future. + // crtpCommanderHighLevelStop(); + // } } void commanderNotifySetpointsStop(int remainValidMillisecs) @@ -96,46 +100,48 @@ void commanderNotifySetpointsStop(int remainValidMillisecs) // COMMANDER_WDT_TIMEOUT_SHUTDOWN - M2T(remainValidMillisecs), // currentTime // ); - int timeSetback = MIN( - COMMANDER_WDT_TIMEOUT_SHUTDOWN - remainValidMillisecs, - currentTime - ); - xQueuePeek(setpointQueue, &tempSetpoint, 0); - tempSetpoint.timestamp = currentTime - timeSetback; - xQueueOverwrite(setpointQueue, &tempSetpoint); - crtpCommanderHighLevelTellState(&lastState); + // int timeSetback = MIN( + // COMMANDER_WDT_TIMEOUT_SHUTDOWN - remainValidMillisecs, + // currentTime + // ); + // xQueuePeek(setpointQueue, &tempSetpoint, 0); + // tempSetpoint.timestamp = currentTime - timeSetback; + // xQueueOverwrite(setpointQueue, &tempSetpoint); + // crtpCommanderHighLevelTellState(&lastState); } void commanderGetSetpoint(setpoint_t *setpoint, const state_t *state) { - xQueuePeek(setpointQueue, setpoint, 0); - lastUpdate = setpoint->timestamp; - uint32_t currentTime = xTaskGetTickCount(); + //COMMENTED FIRMWARE - if ((currentTime - setpoint->timestamp) > COMMANDER_WDT_TIMEOUT_SHUTDOWN) { - if (enableHighLevel) { - crtpCommanderHighLevelGetSetpoint(setpoint, state); - } - if (!enableHighLevel || crtpCommanderHighLevelIsStopped()) { - memcpy(setpoint, &nullSetpoint, sizeof(nullSetpoint)); - } - } else if ((currentTime - setpoint->timestamp) > COMMANDER_WDT_TIMEOUT_STABILIZE) { - xQueueOverwrite(priorityQueue, &priorityDisable); - // Leveling ... - setpoint->mode.x = modeDisable; - setpoint->mode.y = modeDisable; - setpoint->mode.roll = modeAbs; - setpoint->mode.pitch = modeAbs; - setpoint->mode.yaw = modeVelocity; - setpoint->attitude.roll = 0; - setpoint->attitude.pitch = 0; - setpoint->attitudeRate.yaw = 0; + // xQueuePeek(setpointQueue, setpoint, 0); + // lastUpdate = setpoint->timestamp; + // uint32_t currentTime = xTaskGetTickCount(); + + // if ((currentTime - setpoint->timestamp) > COMMANDER_WDT_TIMEOUT_SHUTDOWN) { + // if (enableHighLevel) { + // crtpCommanderHighLevelGetSetpoint(setpoint, state); + // } + // if (!enableHighLevel || crtpCommanderHighLevelIsStopped()) { + // memcpy(setpoint, &nullSetpoint, sizeof(nullSetpoint)); + // } + // } else if ((currentTime - setpoint->timestamp) > COMMANDER_WDT_TIMEOUT_STABILIZE) { + // xQueueOverwrite(priorityQueue, &priorityDisable); + // // Leveling ... + // setpoint->mode.x = modeDisable; + // setpoint->mode.y = modeDisable; + // setpoint->mode.roll = modeAbs; + // setpoint->mode.pitch = modeAbs; + // setpoint->mode.yaw = modeVelocity; + // setpoint->attitude.roll = 0; + // setpoint->attitude.pitch = 0; + // setpoint->attitudeRate.yaw = 0; // Keep Z as it is - } + // } // This copying is not strictly necessary because stabilizer.c already keeps // a static state_t containing the most recent state estimate. However, it is // not accessible by the public interface. - lastState = *state; + // lastState = *state; } bool commanderTest(void) @@ -145,15 +151,16 @@ bool commanderTest(void) uint32_t commanderGetInactivityTime(void) { - return xTaskGetTickCount() - lastUpdate; + // return xTaskGetTickCount() - lastUpdate; + return 1; } int commanderGetActivePriority(void) { int priority; - const BaseType_t peekResult = xQueuePeek(priorityQueue, &priority, 0); - ASSERT(peekResult == pdTRUE); + // const BaseType_t peekResult = xQueuePeek(priorityQueue, &priority, 0); + // ASSERT(peekResult == pdTRUE); return priority; } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/controller_pid.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/controller_pid.c index 5a28d4647..b34420977 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/controller_pid.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/controller_pid.c @@ -9,7 +9,7 @@ #include "log.h" #include "param.h" -#include "math3d.h" +// #include "math3d.h" #define ATTITUDE_UPDATE_DT (float)(1.0f/ATTITUDE_RATE) diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/crtp.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/crtp.c index 04ac7a3ef..090f7718d 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/crtp.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/crtp.c @@ -86,197 +86,202 @@ STATIC_MEM_TASK_ALLOC_STACK_NO_DMA_CCM_SAFE(crtpRxTask, CRTP_RX_TASK_STACKSIZE); void crtpInit(void) { - if(isInit) - return; + // if(isInit) + // return; - txQueue = xQueueCreate(CRTP_TX_QUEUE_SIZE, sizeof(CRTPPacket)); - DEBUG_QUEUE_MONITOR_REGISTER(txQueue); + // txQueue = xQueueCreate(CRTP_TX_QUEUE_SIZE, sizeof(CRTPPacket)); + // DEBUG_QUEUE_MONITOR_REGISTER(txQueue); - STATIC_MEM_TASK_CREATE(crtpTxTask, crtpTxTask, CRTP_TX_TASK_NAME, NULL, CRTP_TX_TASK_PRI); - STATIC_MEM_TASK_CREATE(crtpRxTask, crtpRxTask, CRTP_RX_TASK_NAME, NULL, CRTP_RX_TASK_PRI); + // STATIC_MEM_TASK_CREATE(crtpTxTask, crtpTxTask, CRTP_TX_TASK_NAME, NULL, CRTP_TX_TASK_PRI); + // STATIC_MEM_TASK_CREATE(crtpRxTask, crtpRxTask, CRTP_RX_TASK_NAME, NULL, CRTP_RX_TASK_PRI); - isInit = true; + // isInit = true; } bool crtpTest(void) { - return isInit; + //return isInit; + return -1; } void crtpInitTaskQueue(CRTPPort portId) { - ASSERT(queues[portId] == NULL); + // ASSERT(queues[portId] == NULL); - queues[portId] = xQueueCreate(CRTP_RX_QUEUE_SIZE, sizeof(CRTPPacket)); - DEBUG_QUEUE_MONITOR_REGISTER(queues[portId]); + // queues[portId] = xQueueCreate(CRTP_RX_QUEUE_SIZE, sizeof(CRTPPacket)); + // DEBUG_QUEUE_MONITOR_REGISTER(queues[portId]); } int crtpReceivePacket(CRTPPort portId, CRTPPacket *p) { - ASSERT(queues[portId]); - ASSERT(p); + // ASSERT(queues[portId]); + // ASSERT(p); - return xQueueReceive(queues[portId], p, 0); + // return xQueueReceive(queues[portId], p, 0); } int crtpReceivePacketBlock(CRTPPort portId, CRTPPacket *p) { - ASSERT(queues[portId]); - ASSERT(p); + // ASSERT(queues[portId]); + // ASSERT(p); - return xQueueReceive(queues[portId], p, portMAX_DELAY); + // return xQueueReceive(queues[portId], p, portMAX_DELAY); + return -1; } int crtpReceivePacketWait(CRTPPort portId, CRTPPacket *p, int wait) { - ASSERT(queues[portId]); - ASSERT(p); + // ASSERT(queues[portId]); + // ASSERT(p); - return xQueueReceive(queues[portId], p, M2T(wait)); + // //return xQueueReceive(queues[portId], p, M2T(wait)); + return (wait); } int crtpGetFreeTxQueuePackets(void) { - return (CRTP_TX_QUEUE_SIZE - uxQueueMessagesWaiting(txQueue)); + // return (CRTP_TX_QUEUE_SIZE - uxQueueMessagesWaiting(txQueue)); } void crtpTxTask(void *param) { - CRTPPacket p; - - while (true) - { - if (link != &nopLink) - { - if (xQueueReceive(txQueue, &p, portMAX_DELAY) == pdTRUE) - { - // Keep testing, if the link changes to USB it will go though - while (link->sendPacket(&p) == false) - { - // Relaxation time - vTaskDelay(M2T(10)); - } - stats.txCount++; - updateStats(); - } - } - else - { - vTaskDelay(M2T(10)); - } - } + // CRTPPacket p; + + // while (true) + // { + // if (link != &nopLink) + // { + // if (xQueueReceive(txQueue, &p, portMAX_DELAY) == pdTRUE) + // { + // // Keep testing, if the link changes to USB it will go though + // while (link->sendPacket(&p) == false) + // { + // // Relaxation time + // // vTaskDelay(M2T(10)); + // } + // stats.txCount++; + // updateStats(); + // } + // } + // else + // { + // // vTaskDelay(M2T(10)); + // } + // } } void crtpRxTask(void *param) { - CRTPPacket p; - - while (true) - { - if (link != &nopLink) - { - if (!link->receivePacket(&p)) - { - if (queues[p.port]) - { - // Block, since we should never drop a packet - xQueueSend(queues[p.port], &p, portMAX_DELAY); - } - - if (callbacks[p.port]) - { - callbacks[p.port](&p); - } - - stats.rxCount++; - updateStats(); - } - } - else - { - vTaskDelay(M2T(10)); - } - } + // CRTPPacket p; + + // while (true) + // { + // if (link != &nopLink) + // { + // if (!link->receivePacket(&p)) + // { + // if (queues[p.port]) + // { + // // Block, since we should never drop a packet + // xQueueSend(queues[p.port], &p, portMAX_DELAY); + // } + + // if (callbacks[p.port]) + // { + // callbacks[p.port](&p); + // } + + // stats.rxCount++; + // updateStats(); + // } + // } + // else + // { + // // vTaskDelay(M2T(10)); + // } + // } } void crtpRegisterPortCB(int port, CrtpCallback cb) { - if (port>CRTP_NBR_OF_PORTS) - return; + // if (port>CRTP_NBR_OF_PORTS) + // return; - callbacks[port] = cb; + // callbacks[port] = cb; } int crtpSendPacket(CRTPPacket *p) { - ASSERT(p); - ASSERT(p->size <= CRTP_MAX_DATA_SIZE); + // ASSERT(p); + // ASSERT(p->size <= CRTP_MAX_DATA_SIZE); - return xQueueSend(txQueue, p, 0); + // return xQueueSend(txQueue, p, 0); + return -1; } int crtpSendPacketBlock(CRTPPacket *p) { - ASSERT(p); - ASSERT(p->size <= CRTP_MAX_DATA_SIZE); + // ASSERT(p); + // ASSERT(p->size <= CRTP_MAX_DATA_SIZE); - return xQueueSend(txQueue, p, portMAX_DELAY); + // return xQueueSend(txQueue, p, portMAX_DELAY); + return -1; } int crtpReset(void) { - xQueueReset(txQueue); - if (link->reset) { - link->reset(); - } + // xQueueReset(txQueue); + // if (link->reset) { + // link->reset(); + // } return 0; } bool crtpIsConnected(void) { - if (link->isConnected) - return link->isConnected(); + // if (link->isConnected) + // return link->isConnected(); return true; } void crtpSetLink(struct crtpLinkOperations * lk) { - if(link) - link->setEnable(false); - - if (lk) - link = lk; - else - link = &nopLink; - - link->setEnable(true); -} - -static int nopFunc(void) -{ - return ENETDOWN; -} - -static void clearStats() -{ - stats.rxCount = 0; - stats.txCount = 0; -} - -static void updateStats() -{ - uint32_t now = xTaskGetTickCount(); - if (now > stats.nextStatisticsTime) { - float interval = now - stats.previousStatisticsTime; - stats.rxRate = (uint16_t)(1000.0f * stats.rxCount / interval); - stats.txRate = (uint16_t)(1000.0f * stats.txCount / interval); - - clearStats(); - stats.previousStatisticsTime = now; - stats.nextStatisticsTime = now + STATS_INTERVAL; - } +// if(link) +// link->setEnable(false); + +// if (lk) +// link = lk; +// else +// link = &nopLink; + +// link->setEnable(true); +// } + +// static int nopFunc(void) +// { +// return ENETDOWN; +// } + +// static void clearStats() +// { +// stats.rxCount = 0; +// stats.txCount = 0; +// } + +// static void updateStats() +// { +// uint32_t now = xTaskGetTickCount(); +// if (now > stats.nextStatisticsTime) { +// float interval = now - stats.previousStatisticsTime; +// stats.rxRate = (uint16_t)(1000.0f * stats.rxCount / interval); +// stats.txRate = (uint16_t)(1000.0f * stats.txCount / interval); + +// clearStats(); +// stats.previousStatisticsTime = now; +// stats.nextStatisticsTime = now + STATS_INTERVAL; +// } } LOG_GROUP_START(crtp) diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/crtp_commander_high_level.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/crtp_commander_high_level.c index 273db2e7f..59d59f749 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/crtp_commander_high_level.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/crtp_commander_high_level.c @@ -118,7 +118,7 @@ static const MemoryHandlerDef_t memDef = { .write = handleMemWrite, }; -STATIC_MEM_TASK_ALLOC(crtpCommanderHighLevelTask, CMD_HIGH_LEVEL_TASK_STACKSIZE); +//STATIC_MEM_TASK_ALLOC(crtpCommanderHighLevelTask, CMD_HIGH_LEVEL_TASK_STACKSIZE); // CRTP Packet definitions @@ -224,8 +224,8 @@ struct data_start_trajectory { // starts executing a specified trajectory struct data_define_trajectory { - uint8_t trajectoryId; - struct trajectoryDescription description; + uint8_t trajectoryId; + struct trajectoryDescription description; } __attribute__((packed)); // Private functions @@ -246,579 +246,579 @@ static int define_trajectory(const struct data_define_trajectory* data); // Helper functions static struct vec state2vec(struct vec3_s v) { - return mkvec(v.x, v.y, v.z); + //return mkvec(v.x, v.y, v.z); } bool isInGroup(uint8_t g) { - return g == ALL_GROUPS || (g & group_mask) != 0; + //return g == ALL_GROUPS || (g & group_mask) != 0; } void crtpCommanderHighLevelInit(void) { - if (isInit) { - return; - } + // if (isInit) { + // return; + // } - memoryRegisterHandler(&memDef); - plan_init(&planner); + // memoryRegisterHandler(&memDef); + // plan_init(&planner); - //Start the trajectory task - //COMMENTED FIRMWARE - //STATIC_MEM_TASK_CREATE(crtpCommanderHighLevelTask, crtpCommanderHighLevelTask, CMD_HIGH_LEVEL_TASK_NAME, NULL, CMD_HIGH_LEVEL_TASK_PRI); + // //Start the trajectory task + // //COMMENTED FIRMWARE + // //STATIC_MEM_TASK_CREATE(crtpCommanderHighLevelTask, crtpCommanderHighLevelTask, CMD_HIGH_LEVEL_TASK_NAME, NULL, CMD_HIGH_LEVEL_TASK_PRI); - //COMMENTED FIRMWARE - //lockTraj = xSemaphoreCreateMutexStatic(&lockTrajBuffer); + // //COMMENTED FIRMWARE + // //lockTraj = xSemaphoreCreateMutexStatic(&lockTrajBuffer); - pos = vzero(); - vel = vzero(); - yaw = 0; + // pos = vzero(); + // vel = vzero(); + // yaw = 0; - isInit = true; + // isInit = true; } bool crtpCommanderHighLevelIsStopped() { - return plan_is_stopped(&planner); + //return plan_is_stopped(&planner); } void crtpCommanderHighLevelTellState(const state_t *state) { - xSemaphoreTake(lockTraj, portMAX_DELAY); - pos = state2vec(state->position); - vel = state2vec(state->velocity); - yaw = radians(state->attitude.yaw); - xSemaphoreGive(lockTraj); + // xSemaphoreTake(lockTraj, portMAX_DELAY); + // pos = state2vec(state->position); + // vel = state2vec(state->velocity); + // yaw = radians(state->attitude.yaw); + // xSemaphoreGive(lockTraj); } void crtpCommanderHighLevelGetSetpoint(setpoint_t* setpoint, const state_t *state) { - xSemaphoreTake(lockTraj, portMAX_DELAY); - float t = usecTimestamp() / 1e6; - struct traj_eval ev = plan_current_goal(&planner, t); - if (!is_traj_eval_valid(&ev)) { - // programming error - plan_stop(&planner); - } - xSemaphoreGive(lockTraj); - - // if we are on the ground, update the last setpoint with the current state estimate - if (plan_is_stopped(&planner)) { - pos = state2vec(state->position); - vel = state2vec(state->velocity); - yaw = radians(state->attitude.yaw); - } - - if (is_traj_eval_valid(&ev)) { - setpoint->position.x = ev.pos.x; - setpoint->position.y = ev.pos.y; - setpoint->position.z = ev.pos.z; - setpoint->velocity.x = ev.vel.x; - setpoint->velocity.y = ev.vel.y; - setpoint->velocity.z = ev.vel.z; - setpoint->attitude.yaw = degrees(ev.yaw); - setpoint->attitudeRate.roll = degrees(ev.omega.x); - setpoint->attitudeRate.pitch = degrees(ev.omega.y); - setpoint->attitudeRate.yaw = degrees(ev.omega.z); - setpoint->mode.x = modeAbs; - setpoint->mode.y = modeAbs; - setpoint->mode.z = modeAbs; - setpoint->mode.roll = modeDisable; - setpoint->mode.pitch = modeDisable; - setpoint->mode.yaw = modeAbs; - setpoint->mode.quat = modeDisable; - setpoint->acceleration.x = ev.acc.x; - setpoint->acceleration.y = ev.acc.y; - setpoint->acceleration.z = ev.acc.z; - - // store the last setpoint - pos = ev.pos; - vel = ev.vel; - yaw = ev.yaw; - } + // xSemaphoreTake(lockTraj, portMAX_DELAY); + // float t = usecTimestamp() / 1e6; + // struct traj_eval ev = plan_current_goal(&planner, t); + // if (!is_traj_eval_valid(&ev)) { + // // programming error + // plan_stop(&planner); + // } + // xSemaphoreGive(lockTraj); + + // // if we are on the ground, update the last setpoint with the current state estimate + // if (plan_is_stopped(&planner)) { + // pos = state2vec(state->position); + // vel = state2vec(state->velocity); + // yaw = radians(state->attitude.yaw); + // } + + // if (is_traj_eval_valid(&ev)) { + // setpoint->position.x = ev.pos.x; + // setpoint->position.y = ev.pos.y; + // setpoint->position.z = ev.pos.z; + // setpoint->velocity.x = ev.vel.x; + // setpoint->velocity.y = ev.vel.y; + // setpoint->velocity.z = ev.vel.z; + // setpoint->attitude.yaw = degrees(ev.yaw); + // setpoint->attitudeRate.roll = degrees(ev.omega.x); + // setpoint->attitudeRate.pitch = degrees(ev.omega.y); + // setpoint->attitudeRate.yaw = degrees(ev.omega.z); + // setpoint->mode.x = modeAbs; + // setpoint->mode.y = modeAbs; + // setpoint->mode.z = modeAbs; + // setpoint->mode.roll = modeDisable; + // setpoint->mode.pitch = modeDisable; + // setpoint->mode.yaw = modeAbs; + // setpoint->mode.quat = modeDisable; + // setpoint->acceleration.x = ev.acc.x; + // setpoint->acceleration.y = ev.acc.y; + // setpoint->acceleration.z = ev.acc.z; + + // // store the last setpoint + // pos = ev.pos; + // vel = ev.vel; + // yaw = ev.yaw; + // } } static int handleCommand(const enum TrajectoryCommand_e command, const uint8_t* data) { - int ret = 0; - - switch(command) - { - case COMMAND_SET_GROUP_MASK: - ret = set_group_mask((const struct data_set_group_mask*)data); - break; - case COMMAND_TAKEOFF: - ret = takeoff((const struct data_takeoff*)data); - break; - case COMMAND_LAND: - ret = land((const struct data_land*)data); - break; - case COMMAND_TAKEOFF_2: - ret = takeoff2((const struct data_takeoff_2*)data); - break; - case COMMAND_LAND_2: - ret = land2((const struct data_land_2*)data); - break; - case COMMAND_TAKEOFF_WITH_VELOCITY: - ret = takeoff_with_velocity((const struct data_takeoff_with_velocity*)data); - break; - case COMMAND_LAND_WITH_VELOCITY: - ret = land_with_velocity((const struct data_land_with_velocity*)data); - break; - case COMMAND_STOP: - ret = stop((const struct data_stop*)data); - break; - case COMMAND_GO_TO: - ret = go_to((const struct data_go_to*)data); - break; - case COMMAND_START_TRAJECTORY: - ret = start_trajectory((const struct data_start_trajectory*)data); - break; - case COMMAND_DEFINE_TRAJECTORY: - ret = define_trajectory((const struct data_define_trajectory*)data); - break; - default: - ret = ENOEXEC; - break; - } - - return ret; + // int ret = 0; + + // switch(command) + // { + // case COMMAND_SET_GROUP_MASK: + // ret = set_group_mask((const struct data_set_group_mask*)data); + // break; + // case COMMAND_TAKEOFF: + // ret = takeoff((const struct data_takeoff*)data); + // break; + // case COMMAND_LAND: + // ret = land((const struct data_land*)data); + // break; + // case COMMAND_TAKEOFF_2: + // ret = takeoff2((const struct data_takeoff_2*)data); + // break; + // case COMMAND_LAND_2: + // ret = land2((const struct data_land_2*)data); + // break; + // case COMMAND_TAKEOFF_WITH_VELOCITY: + // ret = takeoff_with_velocity((const struct data_takeoff_with_velocity*)data); + // break; + // case COMMAND_LAND_WITH_VELOCITY: + // ret = land_with_velocity((const struct data_land_with_velocity*)data); + // break; + // case COMMAND_STOP: + // ret = stop((const struct data_stop*)data); + // break; + // case COMMAND_GO_TO: + // ret = go_to((const struct data_go_to*)data); + // break; + // case COMMAND_START_TRAJECTORY: + // ret = start_trajectory((const struct data_start_trajectory*)data); + // break; + // case COMMAND_DEFINE_TRAJECTORY: + // ret = define_trajectory((const struct data_define_trajectory*)data); + // break; + // default: + // ret = ENOEXEC; + // break; + // } + + // return ret; } void crtpCommanderHighLevelTask(void * prm) { - CRTPPacket p; - crtpInitTaskQueue(CRTP_PORT_SETPOINT_HL); + // CRTPPacket p; + // crtpInitTaskQueue(CRTP_PORT_SETPOINT_HL); - while(1) { - crtpReceivePacketBlock(CRTP_PORT_SETPOINT_HL, &p); + // while(1) { + // crtpReceivePacketBlock(CRTP_PORT_SETPOINT_HL, &p); - int ret = handleCommand(p.data[0], &p.data[1]); + // int ret = handleCommand(p.data[0], &p.data[1]); - //answer - p.data[3] = ret; - p.size = 4; - crtpSendPacketBlock(&p); - } + // //answer + // p.data[3] = ret; + // p.size = 4; + // crtpSendPacketBlock(&p); + // } } int set_group_mask(const struct data_set_group_mask* data) { - group_mask = data->groupMask; + // group_mask = data->groupMask; - return 0; + // return 0; } int takeoff(const struct data_takeoff* data) { - int result = 0; - if (isInGroup(data->groupMask)) { - xSemaphoreTake(lockTraj, portMAX_DELAY); - float t = usecTimestamp() / 1e6; - result = plan_takeoff(&planner, pos, yaw, data->height, 0.0f, data->duration, t); - xSemaphoreGive(lockTraj); - } - return result; + // int result = 0; + // if (isInGroup(data->groupMask)) { + // xSemaphoreTake(lockTraj, portMAX_DELAY); + // float t = usecTimestamp() / 1e6; + // result = plan_takeoff(&planner, pos, yaw, data->height, 0.0f, data->duration, t); + // xSemaphoreGive(lockTraj); + // } + // return result; } int takeoff2(const struct data_takeoff_2* data) { - int result = 0; - if (isInGroup(data->groupMask)) { - xSemaphoreTake(lockTraj, portMAX_DELAY); - float t = usecTimestamp() / 1e6; + // int result = 0; + // if (isInGroup(data->groupMask)) { + // xSemaphoreTake(lockTraj, portMAX_DELAY); + // float t = usecTimestamp() / 1e6; - float hover_yaw = data->yaw; - if (data->useCurrentYaw) { - hover_yaw = yaw; - } + // float hover_yaw = data->yaw; + // if (data->useCurrentYaw) { + // hover_yaw = yaw; + // } - result = plan_takeoff(&planner, pos, yaw, data->height, hover_yaw, data->duration, t); - xSemaphoreGive(lockTraj); - } - return result; + // result = plan_takeoff(&planner, pos, yaw, data->height, hover_yaw, data->duration, t); + // xSemaphoreGive(lockTraj); + // } + // return result; } int takeoff_with_velocity(const struct data_takeoff_with_velocity* data) { - int result = 0; - if (isInGroup(data->groupMask)) { - xSemaphoreTake(lockTraj, portMAX_DELAY); - float t = usecTimestamp() / 1e6; + // int result = 0; + // if (isInGroup(data->groupMask)) { + // xSemaphoreTake(lockTraj, portMAX_DELAY); + // float t = usecTimestamp() / 1e6; - float hover_yaw = data->yaw; - if (data->useCurrentYaw) { - hover_yaw = yaw; - } + // float hover_yaw = data->yaw; + // if (data->useCurrentYaw) { + // hover_yaw = yaw; + // } - float height = data->height; - if (data->heightIsRelative) { - height += pos.z; - } + // float height = data->height; + // if (data->heightIsRelative) { + // height += pos.z; + // } - float velocity = data->velocity > 0 ? data->velocity : defaultTakeoffVelocity; - //COMMENTED FIRMWARE - float duration = 1;//fabsf(height - pos.z) / velocity; - result = plan_takeoff(&planner, pos, yaw, height, hover_yaw, duration, t); - xSemaphoreGive(lockTraj); - } - return result; + // float velocity = data->velocity > 0 ? data->velocity : defaultTakeoffVelocity; + // //COMMENTED FIRMWARE + // float duration = 1;//fabsf(height - pos.z) / velocity; + // result = plan_takeoff(&planner, pos, yaw, height, hover_yaw, duration, t); + // xSemaphoreGive(lockTraj); + // } + //return result; } int land(const struct data_land* data) { - int result = 0; - if (isInGroup(data->groupMask)) { - xSemaphoreTake(lockTraj, portMAX_DELAY); - float t = usecTimestamp() / 1e6; - result = plan_land(&planner, pos, yaw, data->height, 0.0f, data->duration, t); - xSemaphoreGive(lockTraj); - } - return result; + // int result = 0; + // if (isInGroup(data->groupMask)) { + // xSemaphoreTake(lockTraj, portMAX_DELAY); + // float t = usecTimestamp() / 1e6; + // result = plan_land(&planner, pos, yaw, data->height, 0.0f, data->duration, t); + // xSemaphoreGive(lockTraj); + // } + // return result; } int land2(const struct data_land_2* data) { - int result = 0; - if (isInGroup(data->groupMask)) { - xSemaphoreTake(lockTraj, portMAX_DELAY); - float t = usecTimestamp() / 1e6; + // int result = 0; + // if (isInGroup(data->groupMask)) { + // xSemaphoreTake(lockTraj, portMAX_DELAY); + // float t = usecTimestamp() / 1e6; - float hover_yaw = data->yaw; - if (data->useCurrentYaw) { - hover_yaw = yaw; - } + // float hover_yaw = data->yaw; + // if (data->useCurrentYaw) { + // hover_yaw = yaw; + // } - result = plan_land(&planner, pos, yaw, data->height, hover_yaw, data->duration, t); - xSemaphoreGive(lockTraj); - } - return result; + // result = plan_land(&planner, pos, yaw, data->height, hover_yaw, data->duration, t); + // xSemaphoreGive(lockTraj); + // } + // return result; } int land_with_velocity(const struct data_land_with_velocity* data) { - int result = 0; - if (isInGroup(data->groupMask)) { - xSemaphoreTake(lockTraj, portMAX_DELAY); - float t = usecTimestamp() / 1e6; + // int result = 0; + // if (isInGroup(data->groupMask)) { + // xSemaphoreTake(lockTraj, portMAX_DELAY); + // float t = usecTimestamp() / 1e6; - float hover_yaw = data->yaw; - if (data->useCurrentYaw) { - hover_yaw = yaw; - } + // float hover_yaw = data->yaw; + // if (data->useCurrentYaw) { + // hover_yaw = yaw; + // } - float height = data->height; - if (data->heightIsRelative) { - height = pos.z - height; - } + // float height = data->height; + // if (data->heightIsRelative) { + // height = pos.z - height; + // } - float velocity = data->velocity > 0 ? data->velocity : defaultLandingVelocity; - //COMMENTED FIRMWARE - float duration = 1;//fabsf(height - pos.z) / velocity; - result = plan_land(&planner, pos, yaw, height, hover_yaw, duration, t); - xSemaphoreGive(lockTraj); - } - return result; + // float velocity = data->velocity > 0 ? data->velocity : defaultLandingVelocity; + // //COMMENTED FIRMWARE + // float duration = 1;//fabsf(height - pos.z) / velocity; + // result = plan_land(&planner, pos, yaw, height, hover_yaw, duration, t); + // xSemaphoreGive(lockTraj); + // } + // return result; } int stop(const struct data_stop* data) { - int result = 0; - if (isInGroup(data->groupMask)) { - xSemaphoreTake(lockTraj, portMAX_DELAY); - plan_stop(&planner); - xSemaphoreGive(lockTraj); - } - return result; + // int result = 0; + // if (isInGroup(data->groupMask)) { + // xSemaphoreTake(lockTraj, portMAX_DELAY); + // plan_stop(&planner); + // xSemaphoreGive(lockTraj); + // } + // return result; } int go_to(const struct data_go_to* data) { - static struct traj_eval ev = { - // pos, vel, yaw will be filled before using - .acc = {0.0f, 0.0f, 0.0f}, - .omega = {0.0f, 0.0f, 0.0f}, - }; - - int result = 0; - if (isInGroup(data->groupMask)) { - struct vec hover_pos = mkvec(data->x, data->y, data->z); - xSemaphoreTake(lockTraj, portMAX_DELAY); - float t = usecTimestamp() / 1e6; - if (plan_is_stopped(&planner)) { - ev.pos = pos; - ev.vel = vel; - ev.yaw = yaw; - result = plan_go_to_from(&planner, &ev, data->relative, hover_pos, data->yaw, data->duration, t); - } - else { - result = plan_go_to(&planner, data->relative, hover_pos, data->yaw, data->duration, t); - } - xSemaphoreGive(lockTraj); - } - return result; + // static struct traj_eval ev = { + // // pos, vel, yaw will be filled before using + // .acc = {0.0f, 0.0f, 0.0f}, + // .omega = {0.0f, 0.0f, 0.0f}, + // }; + + // int result = 0; + // if (isInGroup(data->groupMask)) { + // struct vec hover_pos = mkvec(data->x, data->y, data->z); + // xSemaphoreTake(lockTraj, portMAX_DELAY); + // float t = usecTimestamp() / 1e6; + // if (plan_is_stopped(&planner)) { + // ev.pos = pos; + // ev.vel = vel; + // ev.yaw = yaw; + // result = plan_go_to_from(&planner, &ev, data->relative, hover_pos, data->yaw, data->duration, t); + // } + // else { + // result = plan_go_to(&planner, data->relative, hover_pos, data->yaw, data->duration, t); + // } + // xSemaphoreGive(lockTraj); + // } + // return result; } int start_trajectory(const struct data_start_trajectory* data) { - int result = 0; - if (isInGroup(data->groupMask)) { - if (data->trajectoryId < NUM_TRAJECTORY_DEFINITIONS) { - struct trajectoryDescription* trajDesc = &trajectory_descriptions[data->trajectoryId]; - if ( trajDesc->trajectoryLocation == TRAJECTORY_LOCATION_MEM - && trajDesc->trajectoryType == CRTP_CHL_TRAJECTORY_TYPE_POLY4D) { - xSemaphoreTake(lockTraj, portMAX_DELAY); - float t = usecTimestamp() / 1e6; - trajectory.t_begin = t; - trajectory.timescale = data->timescale; - trajectory.n_pieces = trajDesc->trajectoryIdentifier.mem.n_pieces; - trajectory.pieces = (struct poly4d*)&trajectories_memory[trajDesc->trajectoryIdentifier.mem.offset]; - if (data->relative) { - trajectory.shift = vzero(); - struct traj_eval traj_init; - if (data->reversed) { - traj_init = piecewise_eval_reversed(&trajectory, trajectory.t_begin); - } - else { - traj_init = piecewise_eval(&trajectory, trajectory.t_begin); - } - struct vec shift_pos = vsub(pos, traj_init.pos); - trajectory.shift = shift_pos; - } else { - trajectory.shift = vzero(); - } - result = plan_start_trajectory(&planner, &trajectory, data->reversed); - xSemaphoreGive(lockTraj); - } else if (trajDesc->trajectoryLocation == TRAJECTORY_LOCATION_MEM - && trajDesc->trajectoryType == CRTP_CHL_TRAJECTORY_TYPE_POLY4D_COMPRESSED) { - - if (data->timescale != 1 || data->reversed) { - result = ENOEXEC; - } else { - xSemaphoreTake(lockTraj, portMAX_DELAY); - float t = usecTimestamp() / 1e6; - piecewise_compressed_load( - &compressed_trajectory, - &trajectories_memory[trajDesc->trajectoryIdentifier.mem.offset] - ); - compressed_trajectory.t_begin = t; - if (data->relative) { - struct traj_eval traj_init = piecewise_compressed_eval( - &compressed_trajectory, compressed_trajectory.t_begin - ); - struct vec shift_pos = vsub(pos, traj_init.pos); - compressed_trajectory.shift = shift_pos; - } else { - compressed_trajectory.shift = vzero(); - } - result = plan_start_compressed_trajectory(&planner, &compressed_trajectory); - xSemaphoreGive(lockTraj); - } - - } - } - } - return result; + // int result = 0; + // if (isInGroup(data->groupMask)) { + // if (data->trajectoryId < NUM_TRAJECTORY_DEFINITIONS) { + // struct trajectoryDescription* trajDesc = &trajectory_descriptions[data->trajectoryId]; + // if ( trajDesc->trajectoryLocation == TRAJECTORY_LOCATION_MEM + // && trajDesc->trajectoryType == CRTP_CHL_TRAJECTORY_TYPE_POLY4D) { + // xSemaphoreTake(lockTraj, portMAX_DELAY); + // float t = usecTimestamp() / 1e6; + // trajectory.t_begin = t; + // trajectory.timescale = data->timescale; + // trajectory.n_pieces = trajDesc->trajectoryIdentifier.mem.n_pieces; + // trajectory.pieces = (struct poly4d*)&trajectories_memory[trajDesc->trajectoryIdentifier.mem.offset]; + // if (data->relative) { + // trajectory.shift = vzero(); + // struct traj_eval traj_init; + // if (data->reversed) { + // traj_init = piecewise_eval_reversed(&trajectory, trajectory.t_begin); + // } + // else { + // traj_init = piecewise_eval(&trajectory, trajectory.t_begin); + // } + // struct vec shift_pos = vsub(pos, traj_init.pos); + // trajectory.shift = shift_pos; + // } else { + // trajectory.shift = vzero(); + // } + // result = plan_start_trajectory(&planner, &trajectory, data->reversed); + // xSemaphoreGive(lockTraj); + // } else if (trajDesc->trajectoryLocation == TRAJECTORY_LOCATION_MEM + // && trajDesc->trajectoryType == CRTP_CHL_TRAJECTORY_TYPE_POLY4D_COMPRESSED) { + + // if (data->timescale != 1 || data->reversed) { + // result = ENOEXEC; + // } else { + // xSemaphoreTake(lockTraj, portMAX_DELAY); + // float t = usecTimestamp() / 1e6; + // piecewise_compressed_load( + // &compressed_trajectory, + // &trajectories_memory[trajDesc->trajectoryIdentifier.mem.offset] + // ); + // compressed_trajectory.t_begin = t; + // if (data->relative) { + // struct traj_eval traj_init = piecewise_compressed_eval( + // &compressed_trajectory, compressed_trajectory.t_begin + // ); + // struct vec shift_pos = vsub(pos, traj_init.pos); + // compressed_trajectory.shift = shift_pos; + // } else { + // compressed_trajectory.shift = vzero(); + // } + // result = plan_start_compressed_trajectory(&planner, &compressed_trajectory); + // xSemaphoreGive(lockTraj); + // } + + // } + // } + // } + // return result; } int define_trajectory(const struct data_define_trajectory* data) { - if (data->trajectoryId >= NUM_TRAJECTORY_DEFINITIONS) { - return ENOEXEC; - } - trajectory_descriptions[data->trajectoryId] = data->description; - return 0; + // if (data->trajectoryId >= NUM_TRAJECTORY_DEFINITIONS) { + // return ENOEXEC; + // } + // trajectory_descriptions[data->trajectoryId] = data->description; + // return 0; } static bool handleMemRead(const uint32_t memAddr, const uint8_t readLen, uint8_t* buffer) { - return crtpCommanderHighLevelReadTrajectory(memAddr, readLen, buffer); + // return crtpCommanderHighLevelReadTrajectory(memAddr, readLen, buffer); } static bool handleMemWrite(const uint32_t memAddr, const uint8_t writeLen, const uint8_t* buffer) { - return crtpCommanderHighLevelWriteTrajectory(memAddr, writeLen, buffer); + // return crtpCommanderHighLevelWriteTrajectory(memAddr, writeLen, buffer); } uint8_t* initCrtpPacket(CRTPPacket* packet, const enum TrajectoryCommand_e command) { - packet->port = CRTP_PORT_SETPOINT_HL; - packet->data[0] = command; - return &packet->data[1]; + // packet->port = CRTP_PORT_SETPOINT_HL; + // packet->data[0] = command; + // return &packet->data[1]; } int crtpCommanderHighLevelTakeoff(const float absoluteHeight_m, const float duration_s) { - struct data_takeoff_2 data = - { - .height = absoluteHeight_m, - .duration = duration_s, - .useCurrentYaw = true, - .groupMask = ALL_GROUPS, - }; + // struct data_takeoff_2 data = + // { + // .height = absoluteHeight_m, + // .duration = duration_s, + // .useCurrentYaw = true, + // .groupMask = ALL_GROUPS, + // }; - return handleCommand(COMMAND_TAKEOFF_2, (const uint8_t*)&data); + // return handleCommand(COMMAND_TAKEOFF_2, (const uint8_t*)&data); } int crtpCommanderHighLevelTakeoffYaw(const float absoluteHeight_m, const float duration_s, const float yaw) { - struct data_takeoff_2 data = - { - .height = absoluteHeight_m, - .duration = duration_s, - .useCurrentYaw = false, - .yaw = yaw, - .groupMask = ALL_GROUPS, - }; + // struct data_takeoff_2 data = + // { + // .height = absoluteHeight_m, + // .duration = duration_s, + // .useCurrentYaw = false, + // .yaw = yaw, + // .groupMask = ALL_GROUPS, + // }; - return handleCommand(COMMAND_TAKEOFF_2, (const uint8_t*)&data); + // return handleCommand(COMMAND_TAKEOFF_2, (const uint8_t*)&data); } int crtpCommanderHighLevelTakeoffWithVelocity(const float height_m, const float velocity_m_s, bool relative) { - struct data_takeoff_with_velocity data = - { - .height = height_m, - .heightIsRelative = relative, - .velocity = velocity_m_s, - .useCurrentYaw = true, - .groupMask = ALL_GROUPS, - }; + // struct data_takeoff_with_velocity data = + // { + // .height = height_m, + // .heightIsRelative = relative, + // .velocity = velocity_m_s, + // .useCurrentYaw = true, + // .groupMask = ALL_GROUPS, + // }; - return handleCommand(COMMAND_TAKEOFF_WITH_VELOCITY, (const uint8_t*)&data); + // return handleCommand(COMMAND_TAKEOFF_WITH_VELOCITY, (const uint8_t*)&data); } int crtpCommanderHighLevelLand(const float absoluteHeight_m, const float duration_s) { - struct data_land_2 data = - { - .height = absoluteHeight_m, - .duration = duration_s, - .useCurrentYaw = true, - .groupMask = ALL_GROUPS, - }; + // struct data_land_2 data = + // { + // .height = absoluteHeight_m, + // .duration = duration_s, + // .useCurrentYaw = true, + // .groupMask = ALL_GROUPS, + // }; - return handleCommand(COMMAND_LAND_2, (const uint8_t*)&data); + // return handleCommand(COMMAND_LAND_2, (const uint8_t*)&data); } int crtpCommanderHighLevelLandWithVelocity(const float height_m, const float velocity_m_s, bool relative) { - struct data_land_with_velocity data = - { - .height = height_m, - .heightIsRelative = relative, - .velocity = velocity_m_s, - .useCurrentYaw = true, - .groupMask = ALL_GROUPS, - }; + // struct data_land_with_velocity data = + // { + // .height = height_m, + // .heightIsRelative = relative, + // .velocity = velocity_m_s, + // .useCurrentYaw = true, + // .groupMask = ALL_GROUPS, + // }; - return handleCommand(COMMAND_LAND_WITH_VELOCITY, (const uint8_t*)&data); + // return handleCommand(COMMAND_LAND_WITH_VELOCITY, (const uint8_t*)&data); } int crtpCommanderHighLevelLandYaw(const float absoluteHeight_m, const float duration_s, const float yaw) { - struct data_land_2 data = - { - .height = absoluteHeight_m, - .duration = duration_s, - .useCurrentYaw = false, - .yaw = yaw, - .groupMask = ALL_GROUPS, - }; + // struct data_land_2 data = + // { + // .height = absoluteHeight_m, + // .duration = duration_s, + // .useCurrentYaw = false, + // .yaw = yaw, + // .groupMask = ALL_GROUPS, + // }; - return handleCommand(COMMAND_LAND_2, (const uint8_t*)&data); + // return handleCommand(COMMAND_LAND_2, (const uint8_t*)&data); } int crtpCommanderHighLevelStop() -{ - struct data_stop data = - { - .groupMask = ALL_GROUPS, - }; + { +// struct data_stop data = +// { +// .groupMask = ALL_GROUPS, +// }; - return handleCommand(COMMAND_STOP, (const uint8_t*)&data); +// return handleCommand(COMMAND_STOP, (const uint8_t*)&data); } int crtpCommanderHighLevelGoTo(const float x, const float y, const float z, const float yaw, const float duration_s, const bool relative) { - struct data_go_to data = - { - .x = x, - .y = y, - .z = z, - .yaw = yaw, - .duration = duration_s, - .relative = relative, - .groupMask = ALL_GROUPS, - }; + // struct data_go_to data = + // { + // .x = x, + // .y = y, + // .z = z, + // .yaw = yaw, + // .duration = duration_s, + // .relative = relative, + // .groupMask = ALL_GROUPS, + // }; - return handleCommand(COMMAND_GO_TO, (const uint8_t*)&data); + // return handleCommand(COMMAND_GO_TO, (const uint8_t*)&data); } bool crtpCommanderHighLevelIsTrajectoryDefined(uint8_t trajectoryId) { - return ( - trajectoryId < NUM_TRAJECTORY_DEFINITIONS && - trajectory_descriptions[trajectoryId].trajectoryLocation != TRAJECTORY_LOCATION_INVALID - ); + // return ( + // trajectoryId < NUM_TRAJECTORY_DEFINITIONS && + // trajectory_descriptions[trajectoryId].trajectoryLocation != TRAJECTORY_LOCATION_INVALID + // ); } int crtpCommanderHighLevelStartTrajectory(const uint8_t trajectoryId, const float timeScale, const bool relative, const bool reversed) { - struct data_start_trajectory data = - { - .trajectoryId = trajectoryId, - .timescale = timeScale, - .relative = relative, - .reversed = reversed, - .groupMask = ALL_GROUPS, - }; + // struct data_start_trajectory data = + // { + // .trajectoryId = trajectoryId, + // .timescale = timeScale, + // .relative = relative, + // .reversed = reversed, + // .groupMask = ALL_GROUPS, + // }; - return handleCommand(COMMAND_START_TRAJECTORY, (const uint8_t*)&data); + // return handleCommand(COMMAND_START_TRAJECTORY, (const uint8_t*)&data); } int crtpCommanderHighLevelDefineTrajectory(const uint8_t trajectoryId, const crtpCommanderTrajectoryType_t type, const uint32_t offset, const uint8_t nPieces) { - struct data_define_trajectory data = - { - .trajectoryId = trajectoryId, - .description.trajectoryLocation = TRAJECTORY_LOCATION_MEM, - .description.trajectoryType = type, - .description.trajectoryIdentifier.mem.offset = offset, - .description.trajectoryIdentifier.mem.n_pieces = nPieces, - }; + // struct data_define_trajectory data = + // { + // .trajectoryId = trajectoryId, + // .description.trajectoryLocation = TRAJECTORY_LOCATION_MEM, + // .description.trajectoryType = type, + // .description.trajectoryIdentifier.mem.offset = offset, + // .description.trajectoryIdentifier.mem.n_pieces = nPieces, + // }; - return handleCommand(COMMAND_DEFINE_TRAJECTORY, (const uint8_t*)&data); + // return handleCommand(COMMAND_DEFINE_TRAJECTORY, (const uint8_t*)&data); } uint32_t crtpCommanderHighLevelTrajectoryMemSize() { - return sizeof(trajectories_memory); + // return sizeof(trajectories_memory); } bool crtpCommanderHighLevelWriteTrajectory(const uint32_t offset, const uint32_t length, const uint8_t* data) { - bool result = false; + // bool result = false; - if ((offset + length) <= sizeof(trajectories_memory)) { - memcpy(&(trajectories_memory[offset]), data, length); - result = true; - } + // if ((offset + length) <= sizeof(trajectories_memory)) { + // memcpy(&(trajectories_memory[offset]), data, length); + // result = true; + // } - return result; + // return result; } bool crtpCommanderHighLevelReadTrajectory(const uint32_t offset, const uint32_t length, uint8_t* destination) { - bool result = false; + // bool result = false; - if (offset + length <= sizeof(trajectories_memory) && memcpy(destination, &(trajectories_memory[offset]), length)) { - result = true; - } + // if (offset + length <= sizeof(trajectories_memory) && memcpy(destination, &(trajectories_memory[offset]), length)) { + // result = true; + // } - return result; + // return result; } bool crtpCommanderHighLevelIsTrajectoryFinished() { - float t = usecTimestamp() / 1e6; - return plan_is_finished(&planner, t); + // float t = usecTimestamp() / 1e6; + // return plan_is_finished(&planner, t); } /** diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/crtp_commander_rpyt.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/crtp_commander_rpyt.c index 26c543f9c..7d879bbee 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/crtp_commander_rpyt.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/crtp_commander_rpyt.c @@ -24,7 +24,7 @@ * */ #include <math.h> -#include "empty_math.h" +// #include "empty_math.h" #include <stdbool.h> #include "crtp_commander.h" diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/crtp_localization_service.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/crtp_localization_service.c index b44449844..ddb697cfb 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/crtp_localization_service.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/crtp_localization_service.c @@ -25,7 +25,7 @@ */ #include <string.h> #include <stdint.h> -#include "empty_math.h" +// #include "empty_math.h" #include "FreeRTOS.h" #include "task.h" @@ -127,108 +127,122 @@ static void extPositionPackedHandler(CRTPPacket* pk); void locSrvInit() { - if (isInit) { - return; - } + //COMMENTED FIRMWARE - uint64_t address = configblockGetRadioAddress(); - my_id = address & 0xFF; + // if (isInit) { + // return; + // } - crtpRegisterPortCB(CRTP_PORT_LOCALIZATION, locSrvCrtpCB); - isInit = true; + // uint64_t address = configblockGetRadioAddress(); + // my_id = address & 0xFF; + + // crtpRegisterPortCB(CRTP_PORT_LOCALIZATION, locSrvCrtpCB); + // isInit = true; } static void locSrvCrtpCB(CRTPPacket* pk) { - switch (pk->channel) - { - case EXT_POSITION: - extPositionHandler(pk); - break; - case GENERIC_TYPE: - genericLocHandle(pk); - break; - case EXT_POSITION_PACKED: - extPositionPackedHandler(pk); - break; - default: - break; - } + //COMMENTED FIRMWARE + + // switch (pk->channel) + // { + // case EXT_POSITION: + // extPositionHandler(pk); + // break; + // case GENERIC_TYPE: + // genericLocHandle(pk); + // break; + // case EXT_POSITION_PACKED: + // extPositionPackedHandler(pk); + // break; + // default: + // break; + // } } static void updateLogFromExtPos() { - ext_pose.x = ext_pos.x; - ext_pose.y = ext_pos.y; - ext_pose.z = ext_pos.z; + //COMMENTED FIRMWARE + + // ext_pose.x = ext_pos.x; + // ext_pose.y = ext_pos.y; + // ext_pose.z = ext_pos.z; } static void extPositionHandler(CRTPPacket* pk) { - const struct CrtpExtPosition* data = (const struct CrtpExtPosition*)pk->data; + //COMMENTED FIRMWARE + + // const struct CrtpExtPosition* data = (const struct CrtpExtPosition*)pk->data; - ext_pos.x = data->x; - ext_pos.y = data->y; - ext_pos.z = data->z; - ext_pos.stdDev = extPosStdDev; - ext_pos.source = MeasurementSourceLocationService; - updateLogFromExtPos(); + // ext_pos.x = data->x; + // ext_pos.y = data->y; + // ext_pos.z = data->z; + // ext_pos.stdDev = extPosStdDev; + // ext_pos.source = MeasurementSourceLocationService; + // updateLogFromExtPos(); - estimatorEnqueuePosition(&ext_pos); - tickOfLastPacket = xTaskGetTickCount(); + // estimatorEnqueuePosition(&ext_pos); + // tickOfLastPacket = xTaskGetTickCount(); } static void extPoseHandler(const CRTPPacket* pk) { - const struct CrtpExtPose* data = (const struct CrtpExtPose*)&pk->data[1]; - - ext_pose.x = data->x; - ext_pose.y = data->y; - ext_pose.z = data->z; - ext_pose.quat.x = data->qx; - ext_pose.quat.y = data->qy; - ext_pose.quat.z = data->qz; - ext_pose.quat.w = data->qw; - ext_pose.stdDevPos = extPosStdDev; - ext_pose.stdDevQuat = extQuatStdDev; - - estimatorEnqueuePose(&ext_pose); - tickOfLastPacket = xTaskGetTickCount(); + //COMMENTED FIRMWARE + + // const struct CrtpExtPose* data = (const struct CrtpExtPose*)&pk->data[1]; + + // ext_pose.x = data->x; + // ext_pose.y = data->y; + // ext_pose.z = data->z; + // ext_pose.quat.x = data->qx; + // ext_pose.quat.y = data->qy; + // ext_pose.quat.z = data->qz; + // ext_pose.quat.w = data->qw; + // ext_pose.stdDevPos = extPosStdDev; + // ext_pose.stdDevQuat = extQuatStdDev; + + // estimatorEnqueuePose(&ext_pose); + // tickOfLastPacket = xTaskGetTickCount(); } static void extPosePackedHandler(const CRTPPacket* pk) { - uint8_t numItems = (pk->size - 1) / sizeof(extPosePackedItem); - for (uint8_t i = 0; i < numItems; ++i) { - const extPosePackedItem* item = (const extPosePackedItem*)&pk->data[1 + i * sizeof(extPosePackedItem)]; - if (item->id == my_id) { - ext_pose.x = item->x / 1000.0f; - ext_pose.y = item->y / 1000.0f; - ext_pose.z = item->z / 1000.0f; - quatdecompress(item->quat, (float *)&ext_pose.quat.q0); - ext_pose.stdDevPos = extPosStdDev; - ext_pose.stdDevQuat = extQuatStdDev; - estimatorEnqueuePose(&ext_pose); - tickOfLastPacket = xTaskGetTickCount(); - } else { - ext_pos.x = item->x / 1000.0f; - ext_pos.y = item->y / 1000.0f; - ext_pos.z = item->z / 1000.0f; - ext_pos.stdDev = extPosStdDev; - peerLocalizationTellPosition(item->id, &ext_pos); - } - } + //COMMENTED FIRMWARE + + // uint8_t numItems = (pk->size - 1) / sizeof(extPosePackedItem); + // for (uint8_t i = 0; i < numItems; ++i) { + // const extPosePackedItem* item = (const extPosePackedItem*)&pk->data[1 + i * sizeof(extPosePackedItem)]; + // if (item->id == my_id) { + // ext_pose.x = item->x / 1000.0f; + // ext_pose.y = item->y / 1000.0f; + // ext_pose.z = item->z / 1000.0f; + // quatdecompress(item->quat, (float *)&ext_pose.quat.q0); + // ext_pose.stdDevPos = extPosStdDev; + // ext_pose.stdDevQuat = extQuatStdDev; + // estimatorEnqueuePose(&ext_pose); + // tickOfLastPacket = xTaskGetTickCount(); + // } else { + // ext_pos.x = item->x / 1000.0f; + // ext_pos.y = item->y / 1000.0f; + // ext_pos.z = item->z / 1000.0f; + // ext_pos.stdDev = extPosStdDev; + // peerLocalizationTellPosition(item->id, &ext_pos); + // } + // } } static void lpsShortLppPacketHandler(CRTPPacket* pk) { - if (pk->size >= 2) { - bool success = lpsSendLppShort(pk->data[1], &pk->data[2], pk->size-2); - - pk->port = CRTP_PORT_LOCALIZATION; - pk->channel = GENERIC_TYPE; - pk->size = 3; - pk->data[0] = LPS_SHORT_LPP_PACKET; - pk->data[2] = success?1:0; - // This is best effort, i.e. the blocking version is not needed - crtpSendPacket(pk); - } + //COMMENTED FIRMWARE + + // if (pk->size >= 2) { + // bool success = lpsSendLppShort(pk->data[1], &pk->data[2], pk->size-2); + + // pk->port = CRTP_PORT_LOCALIZATION; + // pk->channel = GENERIC_TYPE; + // pk->size = 3; + // pk->data[0] = LPS_SHORT_LPP_PACKET; + // pk->data[2] = success?1:0; + // // This is best effort, i.e. the blocking version is not needed + // crtpSendPacket(pk); + // } } typedef union { @@ -242,138 +256,150 @@ typedef union { } __attribute__((packed)) LhPersistArgs_t; static void lhPersistDataWorker(void* arg) { - LhPersistArgs_t* args = (LhPersistArgs_t*) &arg; - - bool result = true; - - for (int baseStation = 0; baseStation < PULSE_PROCESSOR_N_BASE_STATIONS; baseStation++) { - uint16_t mask = 1 << baseStation; - bool storeGeo = (args->geoDataBsField & mask) != 0; - bool storeCalibration = (args->calibrationDataBsField & mask) != 0; - if (! lighthouseStoragePersistData(baseStation, storeGeo, storeCalibration)) { - result = false; - break; - } - } - - CRTPPacket response = { - .port = CRTP_PORT_LOCALIZATION, - .channel = GENERIC_TYPE, - .size = 2, - .data = {LH_PERSIST_DATA, result} - }; - - crtpSendPacketBlock(&response); + //COMMENTED FIRMWARE + + // LhPersistArgs_t* args = (LhPersistArgs_t*) &arg; + + // bool result = true; + + // for (int baseStation = 0; baseStation < PULSE_PROCESSOR_N_BASE_STATIONS; baseStation++) { + // uint16_t mask = 1 << baseStation; + // bool storeGeo = (args->geoDataBsField & mask) != 0; + // bool storeCalibration = (args->calibrationDataBsField & mask) != 0; + // if (! lighthouseStoragePersistData(baseStation, storeGeo, storeCalibration)) { + // result = false; + // break; + // } + // } + + // CRTPPacket response = { + // .port = CRTP_PORT_LOCALIZATION, + // .channel = GENERIC_TYPE, + // .size = 2, + // .data = {LH_PERSIST_DATA, result} + // }; + + // crtpSendPacketBlock(&response); } static void lhPersistDataHandler(CRTPPacket* pk) { - if (pk->size >= (1 + sizeof(LhPersistArgs_t))) { - LhPersistArgs_t* args = (LhPersistArgs_t*) &pk->data[1]; - workerSchedule(lhPersistDataWorker, (void*)args->combinedField); - } + //COMMENTED FIRMWARE + + // if (pk->size >= (1 + sizeof(LhPersistArgs_t))) { + // LhPersistArgs_t* args = (LhPersistArgs_t*) &pk->data[1]; + // workerSchedule(lhPersistDataWorker, (void*)args->combinedField); + // } } static void genericLocHandle(CRTPPacket* pk) { - const uint8_t type = pk->data[0]; - if (pk->size < 1) return; - - switch (type) { - case LPS_SHORT_LPP_PACKET: - lpsShortLppPacketHandler(pk); - break; - case EMERGENCY_STOP: - stabilizerSetEmergencyStop(); - break; - case EMERGENCY_STOP_WATCHDOG: - stabilizerSetEmergencyStopTimeout(DEFAULT_EMERGENCY_STOP_TIMEOUT); - break; - case EXT_POSE: - extPoseHandler(pk); - break; - case EXT_POSE_PACKED: - extPosePackedHandler(pk); - break; - case LH_PERSIST_DATA: - lhPersistDataHandler(pk); - break; - default: - // Nothing here - break; - } + //COMMENTED FIRMWARE + + // const uint8_t type = pk->data[0]; + // if (pk->size < 1) return; + + // switch (type) { + // case LPS_SHORT_LPP_PACKET: + // lpsShortLppPacketHandler(pk); + // break; + // case EMERGENCY_STOP: + // stabilizerSetEmergencyStop(); + // break; + // case EMERGENCY_STOP_WATCHDOG: + // stabilizerSetEmergencyStopTimeout(DEFAULT_EMERGENCY_STOP_TIMEOUT); + // break; + // case EXT_POSE: + // extPoseHandler(pk); + // break; + // case EXT_POSE_PACKED: + // extPosePackedHandler(pk); + // break; + // case LH_PERSIST_DATA: + // lhPersistDataHandler(pk); + // break; + // default: + // // Nothing here + // break; + // } } static void extPositionPackedHandler(CRTPPacket* pk) { - uint8_t numItems = pk->size / sizeof(extPositionPackedItem); - for (uint8_t i = 0; i < numItems; ++i) { - const extPositionPackedItem* item = (const extPositionPackedItem*)&pk->data[i * sizeof(extPositionPackedItem)]; - ext_pos.x = item->x / 1000.0f; - ext_pos.y = item->y / 1000.0f; - ext_pos.z = item->z / 1000.0f; - ext_pos.stdDev = extPosStdDev; - ext_pos.source = MeasurementSourceLocationService; - if (item->id == my_id) { - updateLogFromExtPos(); - estimatorEnqueuePosition(&ext_pos); - tickOfLastPacket = xTaskGetTickCount(); - } - else { - peerLocalizationTellPosition(item->id, &ext_pos); - } - } + //COMMENTED FIRMWARE + + // uint8_t numItems = pk->size / sizeof(extPositionPackedItem); + // for (uint8_t i = 0; i < numItems; ++i) { + // const extPositionPackedItem* item = (const extPositionPackedItem*)&pk->data[i * sizeof(extPositionPackedItem)]; + // ext_pos.x = item->x / 1000.0f; + // ext_pos.y = item->y / 1000.0f; + // ext_pos.z = item->z / 1000.0f; + // ext_pos.stdDev = extPosStdDev; + // ext_pos.source = MeasurementSourceLocationService; + // if (item->id == my_id) { + // updateLogFromExtPos(); + // estimatorEnqueuePosition(&ext_pos); + // tickOfLastPacket = xTaskGetTickCount(); + // } + // else { + // peerLocalizationTellPosition(item->id, &ext_pos); + // } + // } } void locSrvSendRangeFloat(uint8_t id, float range) { - rangePacket *rp = (rangePacket *)pkRange.data; - - ASSERT(rangeIndex <= NBR_OF_RANGES_IN_PACKET); - - if (enableRangeStreamFloat) - { - rp->ranges[rangeIndex].id = id; - rp->ranges[rangeIndex].range = range; - rangeIndex++; - - if (rangeIndex >= 5) - { - rp->type = RANGE_STREAM_FLOAT; - pkRange.port = CRTP_PORT_LOCALIZATION; - pkRange.channel = GENERIC_TYPE; - pkRange.size = sizeof(rangePacket); - // This is best effort, i.e. the blocking version is not needed - crtpSendPacket(&pkRange); - rangeIndex = 0; - } - } + //COMMENTED FIRMWARE + + // rangePacket *rp = (rangePacket *)pkRange.data; + + // ASSERT(rangeIndex <= NBR_OF_RANGES_IN_PACKET); + + // if (enableRangeStreamFloat) + // { + // rp->ranges[rangeIndex].id = id; + // rp->ranges[rangeIndex].range = range; + // rangeIndex++; + + // if (rangeIndex >= 5) + // { + // rp->type = RANGE_STREAM_FLOAT; + // pkRange.port = CRTP_PORT_LOCALIZATION; + // pkRange.channel = GENERIC_TYPE; + // pkRange.size = sizeof(rangePacket); + // // This is best effort, i.e. the blocking version is not needed + // crtpSendPacket(&pkRange); + // rangeIndex = 0; + // } + // } } void locSrvSendLighthouseAngle(int basestation, pulseProcessorResult_t* angles) { - anglePacket *ap = (anglePacket *)LhAngle.data; - - if (enableLighthouseAngleStream) { - ap->basestation = basestation; - - for(uint8_t its = 0; its < NBR_OF_SWEEPS_IN_PACKET; its++) { - float angle_first_sensor = angles->sensorMeasurementsLh1[0].baseStatonMeasurements[basestation].correctedAngles[its]; - ap->sweeps[its].sweep = angle_first_sensor; - - for(uint8_t itd = 0; itd < NBR_OF_SENSOR_DIFFS_IN_PACKET; itd++) { - float angle_other_sensor = angles->sensorMeasurementsLh1[itd + 1].baseStatonMeasurements[basestation].correctedAngles[its]; - uint16_t angle_diff = single2half(angle_first_sensor - angle_other_sensor); - ap->sweeps[its].angleDiffs[itd].angleDiff = angle_diff; - } - } - - ap->type = LH_ANGLE_STREAM; - LhAngle.port = CRTP_PORT_LOCALIZATION; - LhAngle.channel = GENERIC_TYPE; - LhAngle.size = sizeof(anglePacket); - // This is best effort, i.e. the blocking version is not needed - crtpSendPacket(&LhAngle); - } + //COMMENTED FIRMWARE + + // anglePacket *ap = (anglePacket *)LhAngle.data; + + // if (enableLighthouseAngleStream) { + // ap->basestation = basestation; + + // for(uint8_t its = 0; its < NBR_OF_SWEEPS_IN_PACKET; its++) { + // float angle_first_sensor = angles->sensorMeasurementsLh1[0].baseStatonMeasurements[basestation].correctedAngles[its]; + // ap->sweeps[its].sweep = angle_first_sensor; + + // for(uint8_t itd = 0; itd < NBR_OF_SENSOR_DIFFS_IN_PACKET; itd++) { + // float angle_other_sensor = angles->sensorMeasurementsLh1[itd + 1].baseStatonMeasurements[basestation].correctedAngles[its]; + // uint16_t angle_diff = single2half(angle_first_sensor - angle_other_sensor); + // ap->sweeps[its].angleDiffs[itd].angleDiff = angle_diff; + // } + // } + + // ap->type = LH_ANGLE_STREAM; + // LhAngle.port = CRTP_PORT_LOCALIZATION; + // LhAngle.channel = GENERIC_TYPE; + // LhAngle.size = sizeof(anglePacket); + // // This is best effort, i.e. the blocking version is not needed + // crtpSendPacket(&LhAngle); + // } } // This logging group is deprecated diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/crtpservice.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/crtpservice.c index a3b9a4812..d42a2d839 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/crtpservice.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/crtpservice.c @@ -80,7 +80,7 @@ static void crtpSrvTask(void* prm) { case linkEcho: if (echoDelay > 0) { - vTaskDelay(M2T(echoDelay)); + // vTaskDelay(M2T(echoDelay)); } crtpSendPacketBlock(&p); break; diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/log.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/log.c index ee8535d06..29786a998 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/log.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/log.c @@ -49,7 +49,7 @@ #include "cfassert.h" #include "debug.h" #include "static_mem.h" -#include "empty_math.h" +// #include "empty_math.h" #if 0 #define LOG_DEBUG(fmt, ...) DEBUG_PRINT("D/log " fmt, ## __VA_ARGS__) @@ -436,8 +436,8 @@ static int logCreateBlock(unsigned char id, struct ops_setting * settings, int l return ENOMEM; logBlocks[i].id = id; - logBlocks[i].timer = xTimerCreateStatic("logTimer", M2T(1000), pdTRUE, - &logBlocks[i], logBlockTimed, &logBlocks[i].timerBuffer); + // logBlocks[i].timer = xTimerCreateStatic("logTimer", M2T(1000), pdTRUE, + // &logBlocks[i], logBlockTimed, &logBlocks[i].timerBuffer); logBlocks[i].ops = NULL; if (logBlocks[i].timer == NULL) @@ -465,8 +465,8 @@ static int logCreateBlockV2(unsigned char id, struct ops_setting_v2 * settings, return ENOMEM; logBlocks[i].id = id; - logBlocks[i].timer = xTimerCreateStatic("logTimer", M2T(1000), pdTRUE, - &logBlocks[i], logBlockTimed, &logBlocks[i].timerBuffer); + // logBlocks[i].timer = xTimerCreateStatic("logTimer", M2T(1000), pdTRUE, + // &logBlocks[i], logBlockTimed, &logBlocks[i].timerBuffer); logBlocks[i].ops = NULL; if (logBlocks[i].timer == NULL) @@ -670,7 +670,7 @@ static int logStartBlock(int id, unsigned int period) if (period>0) { - xTimerChangePeriod(logBlocks[i].timer, M2T(period), 100); + // xTimerChangePeriod(logBlocks[i].timer, M2T(period), 100); xTimerStart(logBlocks[i].timer, 100); } else { // single-shoot run diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/position_controller_indi.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/position_controller_indi.c index 989c224c7..a039c63fb 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/position_controller_indi.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/position_controller_indi.c @@ -27,7 +27,7 @@ #include "position_controller_indi.h" //#include "math3d.h" -#include "empty_math.h" +// #include "empty_math.h" // Position controller gains float K_xi_x = 1.0f; diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/position_controller_pid.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/position_controller_pid.c index 2fa55dd5c..d36f0a218 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/position_controller_pid.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/position_controller_pid.c @@ -25,7 +25,7 @@ */ //#include <math.h> -#include "empty_math.h" +// #include "empty_math.h" #include "num.h" #include "commander.h" diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/stabilizer.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/stabilizer.c index d3ed129de..a9070418d 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/stabilizer.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/stabilizer.c @@ -1,3 +1,7 @@ + //COMMENTED FIRMWARE + + + /** * || ____ _ __ * +------+ / __ )(_) /_______________ _____ ___ @@ -116,93 +120,93 @@ static void stabilizerTask(void* param); static void calcSensorToOutputLatency(const sensorData_t *sensorData) { - uint64_t outTimestamp = usecTimestamp(); - inToOutLatency = outTimestamp - sensorData->interruptTimestamp; + // uint64_t outTimestamp = usecTimestamp(); + // inToOutLatency = outTimestamp - sensorData->interruptTimestamp; } static void compressState() { - stateCompressed.x = state.position.x * 1000.0f; - stateCompressed.y = state.position.y * 1000.0f; - stateCompressed.z = state.position.z * 1000.0f; - - stateCompressed.vx = state.velocity.x * 1000.0f; - stateCompressed.vy = state.velocity.y * 1000.0f; - stateCompressed.vz = state.velocity.z * 1000.0f; - - stateCompressed.ax = state.acc.x * 9.81f * 1000.0f; - stateCompressed.ay = state.acc.y * 9.81f * 1000.0f; - stateCompressed.az = (state.acc.z + 1) * 9.81f * 1000.0f; - - float const q[4] = { - state.attitudeQuaternion.x, - state.attitudeQuaternion.y, - state.attitudeQuaternion.z, - state.attitudeQuaternion.w}; - stateCompressed.quat = quatcompress(q); - - float const deg2millirad = ((float)M_PI * 1000.0f) / 180.0f; - stateCompressed.rateRoll = sensorData.gyro.x * deg2millirad; - stateCompressed.ratePitch = -sensorData.gyro.y * deg2millirad; - stateCompressed.rateYaw = sensorData.gyro.z * deg2millirad; + // stateCompressed.x = state.position.x * 1000.0f; + // stateCompressed.y = state.position.y * 1000.0f; + // stateCompressed.z = state.position.z * 1000.0f; + + // stateCompressed.vx = state.velocity.x * 1000.0f; + // stateCompressed.vy = state.velocity.y * 1000.0f; + // stateCompressed.vz = state.velocity.z * 1000.0f; + + // stateCompressed.ax = state.acc.x * 9.81f * 1000.0f; + // stateCompressed.ay = state.acc.y * 9.81f * 1000.0f; + // stateCompressed.az = (state.acc.z + 1) * 9.81f * 1000.0f; + + // float const q[4] = { + // state.attitudeQuaternion.x, + // state.attitudeQuaternion.y, + // state.attitudeQuaternion.z, + // state.attitudeQuaternion.w}; + // stateCompressed.quat = quatcompress(q); + + // float const deg2millirad = ((float)M_PI * 1000.0f) / 180.0f; + // stateCompressed.rateRoll = sensorData.gyro.x * deg2millirad; + // stateCompressed.ratePitch = -sensorData.gyro.y * deg2millirad; + // stateCompressed.rateYaw = sensorData.gyro.z * deg2millirad; } static void compressSetpoint() { - setpointCompressed.x = setpoint.position.x * 1000.0f; - setpointCompressed.y = setpoint.position.y * 1000.0f; - setpointCompressed.z = setpoint.position.z * 1000.0f; + // setpointCompressed.x = setpoint.position.x * 1000.0f; + // setpointCompressed.y = setpoint.position.y * 1000.0f; + // setpointCompressed.z = setpoint.position.z * 1000.0f; - setpointCompressed.vx = setpoint.velocity.x * 1000.0f; - setpointCompressed.vy = setpoint.velocity.y * 1000.0f; - setpointCompressed.vz = setpoint.velocity.z * 1000.0f; + // setpointCompressed.vx = setpoint.velocity.x * 1000.0f; + // setpointCompressed.vy = setpoint.velocity.y * 1000.0f; + // setpointCompressed.vz = setpoint.velocity.z * 1000.0f; - setpointCompressed.ax = setpoint.acceleration.x * 1000.0f; - setpointCompressed.ay = setpoint.acceleration.y * 1000.0f; - setpointCompressed.az = setpoint.acceleration.z * 1000.0f; + // setpointCompressed.ax = setpoint.acceleration.x * 1000.0f; + // setpointCompressed.ay = setpoint.acceleration.y * 1000.0f; + // setpointCompressed.az = setpoint.acceleration.z * 1000.0f; } void stabilizerInit(StateEstimatorType estimator) { - if(isInit) - return; + // if(isInit) + // return; - sensorsInit(); - stateEstimatorInit(estimator); - controllerInit(ControllerTypeAny); - powerDistributionInit(); - collisionAvoidanceInit(); - estimatorType = getStateEstimator(); - controllerType = getControllerType(); + // sensorsInit(); + // stateEstimatorInit(estimator); + // controllerInit(ControllerTypeAny); + // powerDistributionInit(); + // collisionAvoidanceInit(); + // estimatorType = getStateEstimator(); + // controllerType = getControllerType(); //COMMENTED FIRMWARE //STATIC_MEM_TASK_CREATE(stabilizerTask, stabilizerTask, STABILIZER_TASK_NAME, NULL, STABILIZER_TASK_PRI); - isInit = true; + // isInit = true; } bool stabilizerTest(void) { - bool pass = true; + // bool pass = true; - pass &= sensorsTest(); - pass &= stateEstimatorTest(); - pass &= controllerTest(); - pass &= powerDistributionTest(); - pass &= collisionAvoidanceTest(); + // pass &= sensorsTest(); + // pass &= stateEstimatorTest(); + // pass &= controllerTest(); + // pass &= powerDistributionTest(); + // pass &= collisionAvoidanceTest(); - return pass; + // return pass; } static void checkEmergencyStopTimeout() { - if (emergencyStopTimeout >= 0) { - emergencyStopTimeout -= 1; + // if (emergencyStopTimeout >= 0) { + // emergencyStopTimeout -= 1; - if (emergencyStopTimeout == 0) { - emergencyStop = true; - } - } + // if (emergencyStopTimeout == 0) { + // emergencyStop = true; + // } + // } } /* The stabilizer loop runs at 1kHz (stock) or 500Hz (kalman). It is the @@ -212,109 +216,113 @@ static void checkEmergencyStopTimeout() static void stabilizerTask(void* param) { - uint32_t tick; - uint32_t lastWakeTime; - - //CHANGED FIRMWARE - vTaskSetApplicationTaskTag(0, (void*)3); - - //Wait for the system to be fully started to start stabilization loop - systemWaitStart(); - - DEBUG_PRINT("Wait for sensor calibration...\n"); - - // Wait for sensors to be calibrated - lastWakeTime = xTaskGetTickCount(); - while(!sensorsAreCalibrated()) { - //COMMENTED FIRMWARE - //vTaskDelayUntil(&lastWakeTime, F2T(RATE_MAIN_LOOP)); - } - // Initialize tick to something else then 0 - tick = 1; - - rateSupervisorInit(&rateSupervisorContext, xTaskGetTickCount(), M2T(1000), 997, 1003, 1); - - DEBUG_PRINT("Ready to fly.\n"); - - while(1) { - // The sensor should unlock at 1kHz - sensorsWaitDataReady(); - - // update sensorData struct (for logging variables) - sensorsAcquire(&sensorData, tick); - - if (healthShallWeRunTest()) { - healthRunTests(&sensorData); - } else { - // allow to update estimator dynamically - if (getStateEstimator() != estimatorType) { - stateEstimatorSwitchTo(estimatorType); - estimatorType = getStateEstimator(); - } - // allow to update controller dynamically - if (getControllerType() != controllerType) { - controllerInit(controllerType); - controllerType = getControllerType(); - } - - stateEstimator(&state, tick); - compressState(); - - commanderGetSetpoint(&setpoint, &state); - compressSetpoint(); - - collisionAvoidanceUpdateSetpoint(&setpoint, &sensorData, &state, tick); - - controller(&control, &setpoint, &sensorData, &state, tick); - - checkEmergencyStopTimeout(); - - // - // The supervisor module keeps track of Crazyflie state such as if - // we are ok to fly, or if the Crazyflie is in flight. - // - supervisorUpdate(&sensorData); - - if (emergencyStop || (systemIsArmed() == false)) { - powerStop(); - } else { - powerDistribution(&control); - } - - // Log data to uSD card if configured - if ( usddeckLoggingEnabled() - && usddeckLoggingMode() == usddeckLoggingMode_SynchronousStabilizer - && RATE_DO_EXECUTE(usddeckFrequency(), tick)) { - usddeckTriggerLogging(); - } - } - calcSensorToOutputLatency(&sensorData); - tick++; - STATS_CNT_RATE_EVENT(&stabilizerRate); - - if (!rateSupervisorValidate(&rateSupervisorContext, xTaskGetTickCount())) { - if (!rateWarningDisplayed) { - DEBUG_PRINT("WARNING: stabilizer loop rate is off (%lu)\n", rateSupervisorLatestCount(&rateSupervisorContext)); - rateWarningDisplayed = true; - } - } - } + // uint32_t tick; + // uint32_t lastWakeTime; + + // //CHANGED FIRMWARE + // vTaskSetApplicationTaskTag(0, (void*)3); + + // //Wait for the system to be fully started to start stabilization loop + // systemWaitStart(); + + // DEBUG_PRINT("Wait for sensor calibration...\n"); + + // // Wait for sensors to be calibrated + // lastWakeTime = xTaskGetTickCount(); + // while(!sensorsAreCalibrated()) { + // //COMMENTED FIRMWARE + // //vTaskDelayUntil(&lastWakeTime, F2T(RATE_MAIN_LOOP)); + // } + // // Initialize tick to something else then 0 + // tick = 1; + + // rateSupervisorInit(&rateSupervisorContext, xTaskGetTickCount(), M2T(1000), 997, 1003, 1); + + // DEBUG_PRINT("Ready to fly.\n"); + + // while(1) { + // // The sensor should unlock at 1kHz + // sensorsWaitDataReady(); + + // // update sensorData struct (for logging variables) + // sensorsAcquire(&sensorData, tick); + + // if (healthShallWeRunTest()) { + // healthRunTests(&sensorData); + // } else { + // // allow to update estimator dynamically + // if (getStateEstimator() != estimatorType) { + // stateEstimatorSwitchTo(estimatorType); + // estimatorType = getStateEstimator(); + // } + // // allow to update controller dynamically + // if (getControllerType() != controllerType) { + // controllerInit(controllerType); + // controllerType = getControllerType(); + // } + + // stateEstimator(&state, tick); + // compressState(); + + // commanderGetSetpoint(&setpoint, &state); + // compressSetpoint(); + + // collisionAvoidanceUpdateSetpoint(&setpoint, &sensorData, &state, tick); + + // controller(&control, &setpoint, &sensorData, &state, tick); + + // checkEmergencyStopTimeout(); + + // // + // // The supervisor module keeps track of Crazyflie state such as if + // // we are ok to fly, or if the Crazyflie is in flight. + // // + // supervisorUpdate(&sensorData); + + // if (emergencyStop || (systemIsArmed() == false)) { + // powerStop(); + // } else { + // powerDistribution(&control); + // } + + // // Log data to uSD card if configured + // if ( usddeckLoggingEnabled() + // && usddeckLoggingMode() == usddeckLoggingMode_SynchronousStabilizer + // && RATE_DO_EXECUTE(usddeckFrequency(), tick)) { + // usddeckTriggerLogging(); + // } + // } + // calcSensorToOutputLatency(&sensorData); + // tick++; + // STATS_CNT_RATE_EVENT(&stabilizerRate); + + // if (!rateSupervisorValidate(&rateSupervisorContext, xTaskGetTickCount())) { + // if (!rateWarningDisplayed) { + // DEBUG_PRINT("WARNING: stabilizer loop rate is off (%lu)\n", rateSupervisorLatestCount(&rateSupervisorContext)); + // rateWarningDisplayed = true; + // } + // } + // } } + //COMMENTED FIRMWARE + void stabilizerSetEmergencyStop() { - emergencyStop = true; + // emergencyStop = true; } void stabilizerResetEmergencyStop() { - emergencyStop = false; + // emergencyStop = false; } void stabilizerSetEmergencyStopTimeout(int timeout) { - emergencyStop = false; - emergencyStopTimeout = timeout; + //COMMENTED FIRMWARE + + // emergencyStop = false; + // emergencyStopTimeout = timeout; } /** diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/system.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/system.c index e273155b0..25ce54c72 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/system.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/system.c @@ -332,25 +332,25 @@ bool systemIsArmed() return armed || forceArm; } -void vApplicationIdleHook( void ) -{ - //COMMENTED FIRMWARE - static uint32_t tickOfLatestWatchdogReset = 0;//M2T(0); - - portTickType tickCount = xTaskGetTickCount(); - - if (tickCount - tickOfLatestWatchdogReset > M2T(WATCHDOG_RESET_PERIOD_MS)) - { - tickOfLatestWatchdogReset = tickCount; - watchdogReset(); - } - - // Enter sleep mode. Does not work when debugging chip with SWD. - // Currently saves about 20mA STM32F405 current consumption (~30%). -#ifndef DEBUG - { __asm volatile ("wfi"); } -#endif -} +//COMMENTED FIRMWARE +// void vApplicationIdleHook( void ) +// { +// static uint32_t tickOfLatestWatchdogReset = 0;//M2T(0); + +// portTickType tickCount = xTaskGetTickCount(); + +// if (tickCount - tickOfLatestWatchdogReset > M2T(WATCHDOG_RESET_PERIOD_MS)) +// { +// tickOfLatestWatchdogReset = tickCount; +// watchdogReset(); +// } + +// // Enter sleep mode. Does not work when debugging chip with SWD. +// // Currently saves about 20mA STM32F405 current consumption (~30%). +// #ifndef DEBUG +// { __asm volatile ("wfi"); } +// #endif +// } /** * This parameter group contain read-only parameters pertaining to the CPU diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/amg8833.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/amg8833.o index 2376aa95779ed0de3a03b696450abe50f484d5e8..433d495f3ec82662fe19ee86b6b0fb6873e25153 100644 GIT binary patch delta 815 zcmZ9Jze^io7{{OIE|FaCN1`#_od%M@A#M?bv{2A19a`vMv_tLUbrTUx>DZw+6mc`@ zlRuyZ2Mt;*F4@}RBG{o0)edbD+NqSHqz(>(@7?<xoPFWFm*?~SexLWp?UcKvW(9Ay z#tzCqRqR}<&`O!Xi~_+7irJgR&7KOK^E_P8AWl?I)O^Pi!m}a_06@E~6c&92Za}U* z+?(|_&+}6km(TY$KB)6YrLy{EcNOoY>o0{h9Lr)30KybTB^2cX0dt?Z!F-K*gZVG! z>oneHzjzy`6p05}-D4gwkGp+k-em5x{|EC^=JBb{nCDb!yv=@bf$$cOVVZ?_15*m% zGmj6{&pcqh&W(!9tEuZ7jFFeI(WAM{3jNLe?vv{7v33jbE_u4`J`~At42hMSM)f0l zs@v4i9k<Jl5wR8`O@8+2P&m4}WBy4x=)0ibbmNubxMhBa|D#nx!^UZPV%TnjJ;S0& ze9dr!)lkLHk#m$j8us`EpD*m@CJwTZ;PH!x@~0^EFQJYkQV;m4!fwgb0@cm;xJ3O{ zO>1g0;8WeIsaq+aH|YYswkpbYir$$+bYfL-hqUY@cIke0QghNW;7}`D)2bO+&C#K# MPWk8Fp_Wy;0(^~bO8@`> delta 891 zcmYk2L1+^}6o%*RCMDb5O`E1>OuK4AFA+UdDWnIX+tNdODAY6;tzZfY#R>)j60y`h ziN_5uLcJ6P4<@HdE<IQ*cqw?&gIMrTX+c3eNa(T9nVlD$ft{K6{qKM8?d)9I&V>co zZe0GHi@8DR)MSk#6WRs~N+7=O612J|Yo9C|EgXgke_FspGu^IvY=|+|%!t#6pd{~X z-A8#gjdKqwMy8()Hb=Tk)2)-`nbzskPw)23yWcu>n2TGRB2BJGnD66IlY44I#6t|& zB197N@LwO#J1SsXqz0rO6Yogxvt3fFhQh<7ekC3f?^XLn{5A0k<^LtlOa(mRVytMk z9Pt~(2Nb`}DkSt8cx0#&?+uhA9uj{`g{~0yV+!;dOd=#WEMhkCJh^ba%pR9lYHPFi zAFe#Xt;C;BXidVrtSQ%MR72h6UeI{@KW1g(X>rmRk$Mk*_H!Jx&qEzkHh1?mKgR`o z41VK#k@3QIfa6OMd-%rY*>QSA*`I5De5uY?NF5QXtEqv;GaBF2xSoF~tHA^|9DZ$< z#+DsNHSdnbFKYZp<ciVTO4kKVy`yp6RmTJ8Bdp^qw`hI0lp(|ew+J6Fm7IcIyealQ mY>0gyza*!uLR@9dVRoQsRTC;&#akj;rJtF>d_0X;lg=51#C6R8 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/app_handler.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/app_handler.o index ab5084c1a5bf06a62af738d0aaf2625d60c89fd2..2e7f54357d3c24a1bd8ffc9b109bd9330d5faf8e 100644 GIT binary patch delta 571 zcmX>gd_Zu5rZ^h|95{ek4h-B3TnrNzSThD~ymN$casd<D<b6y+lNSK#Ye4z}kY2_l zBq<71&BVaSPyp301Eu*VGcw16Ri`n#i7EkAz(5R?5j(k&MO-o;$P)s}CO}15pmaG% zma!d3s<Wgps8mc|!{R8JSWw`Zms!G45t3M(?Oc?aSdtoCl30?NJXxPrQ;LBHs#h3j z8O$7zkig_ZR&hxQsH`ZOtjy$vtm5?wP+5>(Rwx@psUV3n0ogEr>OjRororq52^k=X zBb#G_B#vy33q)LqK^ka~AXE{E@&P(p-V`J%j3inEWrM_pki=V%#6>30WjoB+GdYpn zf{|tNEOtA_Gm{+|#V3DY*I>H9Fj<Pjj`;!u12BF>Cl_#NFy5Hl$Sgd04Tlb6#^jqE k_FN}`MuWf)#>q;YW}F9@A>2um6FDt7pk4}`{E%H905FG2eE<Le literal 2496 zcmd6nJ!lkB5P;`y<8OrcL;N9%t3-*AEO!S1BM7JQ7gVA~6cv(nv&S8|KX+f`LPQU- zw8)8trG-KS3p)!zgN0a%pjcQ~SlURc6fw^1&Ll4{ryw@Yu{$&0o0&K7-Ftic=&57L zL;^$-@B$V+p{Q3a+S$m=LMyBVXo0qAYv|KX+xke)-}-tk<(vN8#H*)s7BpsBVRjS1 z<Zv?E_cZ~%ei9lh(Z^mVv7N~$HZ<M>G<M;Gexn8IA1r+C?5Uqa|A7tlbHhpKn`zC? z&P}|Tl6gc+|8o<sqxmQ&e(Lv0|D2!Sf*RavmDK+y$NT#a*j>lZT(Ac#m7<q-3uQZ3 z32c@3?L$4)ppq*T(F(kLLHV8<3w*oJ$@FAW={_f&vAf)$)Pq)P-#+3_+NP0oD%1Pt zrP5hxfgkhDqO9g82`v0I6ALSu(iVZHClafyFvDSEM3(b*<Vo!3J!foZ9mg-9cL$Cq zw0@+6PUfpQe|QZWs4Tz}X-HguIX{ST2`!!uv52K#Hij2aZ`Afv=D*B*J;w<jVs0DU zXPz?nDDy0H*^yh!2MkXA?#6zGnO|l75H<BV&A!xmgue91Ly>y^8%`H(DDRd>ihkgD z&{>1d5n_XGI0}XEWVxWA5}qFqhZvq$t~YvkESK|xr2~|~+^d8+2n*#L<VtQ0&Fg{6 zLGA3AKj!xbzN>t!q6!|=C}|17S)w^npT?^N;drS0(nYtRFeOlMgEEfzMRz=2U6B{L z2@j6!0ii1M%?7VAZ#Vc&=2T}L+obAj6W34IU5zKve$W0r)>L1wGpTXC4t@McC|<Ag zIL6R{obHs!Gd9e1eP&MaTO}Cv7mY_BR`$PXd>h-5a>DVFa<73Csvy>Ru>#z7NBK1c z&WNjAaIS?RI6;LR3Qs%x!STFOguP0s<d>CR`d@4tlW}QF{sXF)r5DQgSS`HQFIchB zfvN?cZ0s()FYzaAfQqBgy(Uxcx9sI!=H?f*oAYpZiI}(>N2#WnpW?v0_I;y5GC$cQ zX?!R&LyjhrPixaf@}-X~4w7xozn=r-d`b<;7ykt3rv$Km$N5(bF7xV|&bKLD46CeZ n8|c52`DOo!o4r%5hrIBY<Y*%E3fh21v-~N(jAtc~wVD450jB68 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/bstdr_comm_support.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/bstdr_comm_support.o index 757410f56892a75874ed2054bcc7ce12f616848c..426e805a538f26fe60b71cc403bb508bed171ce6 100644 GIT binary patch delta 132 zcmX@Xdw^$x1|!2n&E+fynB%Wad{MGFfzgAJk!A8trumEllP@xhPhP-WG1-G<0ppa( zFImhv4VW3gV8UcgR&&NHlM`9(f#gCk`H<C~(|{2opD|gJ&75-v6NEQoav-Dd<Qg^= N&I3^WRuB<Z9sq10BJ2PF delta 226 zcmX@WbAoq*24lxW&E*n*tM{+`%giv5fq`Ml-|B-a7-}3Q1KA=Iuar!7U}Ty6frVwW z52Fhsrvy+G1ZGTDWD;kb10pBSV4A`2YZSsz7Lr(;?UI_4SjjM1pLwF{42V(&X+{PH zekdD6ErGJ7fZ_s^w=%D0TroM3#hkN)86t6D@<JAK#ut+f8KozGVNrpyOjtpzNLG7J h51>8}m@#=Ft2yTbCJ1l&<cC0>2MdH}HTfZnJOIQJHeUb$ diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/collision_avoidance.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/collision_avoidance.o index 3a299ee8411e64bc8bec07efde6d88af79097880..d1302efa29c024d9f58c8ba585c28c19ded92201 100644 GIT binary patch literal 3032 zcmdUx&ubGw6vrn`)%pXeA{hLED+Eo!E=g2q)k8wjw$MtUsrcg%H_6mpNOqRpwX9yO z7wMnSV{cx2(_@Yvy(k_%dKE9;bYAja@-p3k;>m&K&G)n4_hxo>XOdTUSME(@GJ;x0 zyc0u3REXTsVZYMrR>W~}OmwsL&zG$1C%XPbLwZxSt6MtCcH0Xg<+UF6iVpQ7LqG28 zMnfg5o{w%JP@{XG(T&<kM*U7Q>UWZX-&LXaQu(6eB<q2ct^TM&L|#iqu?%W%7`Yni z`)g8$E2>$2CbiyDVNJDraXFS@G{}opP^X90@HO2q;uS-a{9AsQ5{>x3^9kd5NRE51 zasF*eG~?pJ!Y!+?cz?sHDb;Sej^|sODzsu(TGiPgRGVH~_rj*@#j+Vc52ZD4muJhx z(!5<NTLmZV%<5ioW(K%jvfxgsSiWfvG^$~*O^WZoMrmJVQ+J{eS&{y9S$)TBXL}%R zM?;-S(=N{S$T)tm{zdK2uyOCOidk`pseZR#{~*uz>J0fVn{rkhIZ)@iCa2l@(2QZD z1E0nW;tIKC@Hfbd28RQx?M0sQ>&})wo*cg^?WV{lBHt2$6FQwp)a(5Y?(acHl@d0B zmJ`c$83)Sq;{_GUVcCIc+4tfUT+_!*3LY&f#1zgOj&QygEQ6D;z&Nc9pgG2&P7Za2 zaqv^l8sp%nx^&ROe85ZNx`v;|3m6Cg3Dnz+L;WSxJB)*$-t#Ww;HP=)F%JGSsP`EM zKh5tw<KWMs{=hi+6Vx9W2mb}sUl|8K&HEeU;I~l!WE}jvsOb}@^~@um#{EI>eGhq# zaj0KFUSJ&R)AJV@2mdwnR~QF>7x@z7;4dP7$T;|EU7j)y{u}5I7zh6s<O$>8pF_UG zIQVHDg&n=<#7;xUIP6E4da+DmVe2jE2)hwQ!VVP(aF*;jEoIxWdt2D<|3d4~=}14u zG5;l;*U2ztm@97;6toU>Z<;z7FY5^T=7~FQZn!*yDpz%HDkVQb2S29)ftNS<4xnb4 zL*1wR9|os<nny+7Pn$ozcYeM@DawaFwA=cE_g~Q$Z(aI{z=eT4K$M?D^Qw+8K7F5v z#T4c}A%KzQ&12fHtc&^kXoSDTC-r5H58QlrFjNlb{}u#mG%lf2x|5dQ#ep7>5u=&^ E8=_?Ig#Z8m literal 4632 zcmdUzQEU`d6o$|46sUq&M4;HJiz!$THroo88Us^m1tOZpE~ZLiJKfH*lWup`nE@9t z=^A)wd}<>mU`!<Og>6ji1Bo<&q=^xU`oN3EG%=|fmBbeeA+#a2o-=#S?(K9NHSxtu zhI7w%|8vg0cXsYfI@EFKg>WbY(n9bVls%yU=T?{dy5H4dH9P=N1rJVYJ>NYZ(Y~eY z?|fBD`k)_y{3|M(J2g?5(_r*=SE%qXz{u&a-g+8f*X^#h!rZAZFOv4ok#OO?FpRoS z!06qCR+!O3V|O(en;obs%xdAWd+xGAJ?5>$3#Wb-*EjME!01%7K5++iKeoW^v{t|E z!xgZG#*GzqD>qlcnucoh!*EFhz4h}D?3{v`7OhI3xYnGX_&BV6Jp{{tuMR;Rs`aa< zFt&GU(-l~yU+taRd<AOAHeC7WDR^_!+<bhxMV~#3bNo%)ICci-`Kwkt_KUV*>?f^m z+s|6n7}gyPL1>if)3pxPy?8g#UU>hj&;+gZ&XIkE*@5Q^_uP)sx={xooIk&Zu4FQ~ zcYc0oUb)a2@-Kk=UX<dM-!r@x;FB+&Z0V<9zfBGS$OVwF({0C*n;D}oZK6%5t*mQX z{oO@%$$u^2zh3nF`t00GR)*C8?6bP$vzmP)w@`277V3>$NuRPE>!h85K_l0dHO<m8 zT&v%7Ju@3mIc^H4g5#a0=^U~XZAWn#aNKs{cG|ZGJ=1ZEvjuQHJKH0RMwm7{Gm|(0 z?}#8^wSX^fUOEB0RG!9wPTVch3D|$jmj~j-{lD|DEF@r;TGvwgd?3E$?r(2@HqyBN z<-?J<ZKo3{!^%XGwiEGEW~6OL*0GaT8hcJ6WqD@8JLZ^?)@bvN=2%l}w5d7LXgGsA zuov69m3Xu%LL*JF=3S)<6+3k1R>2?hl?JtnCo+JB|0*>NGX>iQA5fLWO@n2N;3Ga+ ziZ8DFDC$GXe4gWs4a{}+SFtVTUp&vJeSMkBj1Mud=J-h-c$N8e_REp9KZ}1A#k!06 z8-AWLKfra!XdqR~u$X5tA3#Y+(T~dl{5<!U6L9Y&+J}_;D;e=n_IVBKgr8v^3GjEB z$C%4Le9Bx8@N3LFnM?j3nD;WT=lTDMzRZP(d{cwtl{mdf(w1x4nI7XfzCMgh!i*-M zAqNfpkTo1*&@D^4JUn&FZkq&j6kkGb+0KBQH4<j&bnfX%+eckKw|jbu`Pfa^ZW3H8 zlY}I`1d<if9?te-y)M(s+E&JEx1CD04`wW{LTnu0G8OQ`l#q)X?!bQ2i(83-cKcYy z1AJG}%g9JuCk+pG1qVBA*P`ye69@ZqvZwfp^4nV6SGk7-vPBH*1ALhIx&R+%UWc5X zO=*|7L;2OG_%d_Kqw*WfDbHh)1nqY8sRipEP`H|>lR4$tSPb?5k1JfAr~Dr2)3p3l z0z^2r#5ulE;k0jZ9_&^)<+;WFKg}<?V17;m!TdEmptGfUF4zZ!(|jWAcPpIqa_>_L zCw+|ltinkz^UN!p^g8>)3Majs!{-!E`cC#QD4g`Nu5pEvzL)*W3MV~&tNZObTe)8{ z?;8pyeJ%Ub3a9*e_HQbj^!4n|D4g^o?8}iV`yXLW=M^=X&jsJZ`U<D~4a^%APWdk~ zk13q=jm&k0lV0{ko(q}JcGh<X^s-;Q3a9)r)@Kz?`M+nLQ#k2&G9Okr>8F{GD4g`W znO{&i>2EQIsC#12Gy2eaPSK{M=a^|D>X|tYqIj?x5bbkah&nboByWoDMwdi*YDbG7 z+eP0$xP>I_!9f#`%KxNAFbge()}S_>ows?NGFBrUwsmOf8PwSqGjd<CSIzM&(WP!R z3u@VJVNQFiwn>ho?-{j8yfFHG5DUiF@CWTTf%ymHn=qCn&3LIz;${9aCh?NC0|%%d ztY6FEfCRFYc)>b$D(&An{sih}A?+XCBZ-&&JB+MS{a&s=E)(TE63?!Gj#a8Z!}VjF zhw4+T#7q4?WK=?)JM8+chChjq2w*GIQ7zx91<EYP-{e6$hu7m3tWQ6);NDZBZWcC4 YA%fTfuK$OOO7V^ScO3doRa-FrFRuvPHvj+t diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/commander.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/commander.o index e7f89ade1cd3e271ce9d84cbe7e5b842d33dcf58..4549b8b88f3b5f3d0f8a298b89fdf37e55797bab 100644 GIT binary patch literal 2128 zcmbu9&2G~`5XUDqAih;T4hRmcM1@j`x=AEZ%PCbUZKbNJXh1?7QpepAtBD=i+bBH| zZXEjp+>v+yuAF!S5Ley+o&aX-nPj_3Pi$+?%y0iQyPkFYZf)!NOsNDiO7I27kx+o0 z^JBlByLGq<SKzDH{Bd7--{o>+l-`y(vXk?}7dBIHItGrzq}vVReVy_)bi5J0ZExwm z?&KshNv~;%-m}g%WfyQfJcGmf>grQfUf+JH8cEU#+d&kogCtd^t<}mxFHH`j4ti<W zj*Je?QL5FlUt6eEs>^=0rpiIuT|logKTq7RDw?TQYLCxau;6qC=itxZX)15(2?2Qc zH*I)W$sN~nFzuwNj&<0aIGfu^ehYcYsxK7_{p7k-#)AuaHTzcRC;0;ul`Q>+mE^%i zD=OS4Xl`2lksUl^UaUjCEyio+ieuq@j77^+x%q&1s$XF!`j5=(%w=bvneRCK8}mJf z!{{CMLzo-D+&<_yXm#}Xb#FF%K^k;3>vbO`ZN`xqm)O+?|9eRkTW~uu(ZR9sY!`nx zFlYqX;kq`BC_G$Ej%+zn(T)o@bY@jV$z~jcChAA#xDj>rScp?AG@*CWC`oae9~Trm zckzX}ArP(fjXp{C+aP-3ayDhoB`#+{XvyMKM{x{(cHA{V3#~~D+ZHd?oxnGGV8GuG zOaOi>%fL?)3P@h{moOwzegOWc>yWz|+xFjs_KA;j>e;Dioo+bVg&EzY4+8F?Lw%?V zU_0RE+~N2VT3Sc?E&L&K_e=7L^IStU?C}T#s(Dtvt9Ron<`S#nWe-_@(T3>D{-w?u zGV<N^e{$XiTQQO^aUGp${X60Q?Xi&hNAH#7OaERWqxI$cfNnk%Z}5!(wz6;A&Nvzh rhb)-o$;-&D<K?bT`*NQh5u7mmMS(SBT|x9)oR<HapT8+Wwr>7E0V&q? literal 6984 zcmeI1Uu+yl8Nff^8ar*%G>P3NN<zIUZgC1Z|A9(zMd>C^np6#yu`g<+NI2*7IzIXS zWp^FfawX2CK!s4S)jaf}QqrgoKEDvrLO3aa34RC&p@3S1L?mp41V}sprfMAJWWI0b z`|jq(UL@eP6Yb5+Z@z!?&Ft=Y^VMS~pNlm#fRqNf2DP40fSbE&Z6|CxunisrXoQCr zt)btx+13Yi{kMHxm-H*sKPpu$n48&A9I&A{usYaKY6Y16S`6lfo!DFpwm&=_D`5y1 z&%|JD*@E{hDE=mf*TXpWHp<Z$$)6{k#iqF#w38|}&XGMDTWo?g8}&$*boY0~=18B$ z^vlQb{iyTd=_92xJE5E$fZo-?!==jf&*mv^%+oB&(}i;At6AAU6LZ#nzrMc99RDMa zFE%-AD>$y^dp(>l`IouAhJIHqSXk+V^2#dA6&sy3imR;={;>>@5WD1)eBZcF`CaLB z%FE9><!1rLzlCxt)}=63(*G0Lv|1L57+)XyBcCHNC|^W>G`{jK%n>hQe0n}~JC$h_ zFU9&V3!bF4cm#9s0owRzFRWb~R<>eyaqZCGBKkT4tuL%tyB3C^Wjrza#vZZl#}p?S ziRaxtP^MTeUy03;U&{SQd!4n)^wK=?R@ontFN|Sf)oQ?bwJuOBv<H5Gv0O%*WTzN& z%8R&m)SkgMK*I}dPTRQy79<w`+1Cr7fTt**%cxKJe07J~2gBQ(()ZEMl?(TmhPNFq zUAgc8)<>}3igh2>4`O{3>usgvfK#Se-@XfFidXhW+pXqvKd-EZ>qWL{-D$7MTq&j% z3%=*z9=n8l^3r2azVtM#&D?0dQ~U;$|A2dh;-WPpS&H}a-Sy8?yKNtM%XgJ+GxlHe z-U{!>aDO_za-UVEe-iFDvO)8%O#gI#Kd8Kr402>YE>V8zK3wr>J^%Cmd$mRFzvVWk zT$#QR?zecnGn*fo$hdx|@1;6Z`D`|s8*#mO3O!))-Jp<9=YlU!xDzh+3tl?!rGu$z z-*v|aTz?`H*v~v;7e*2Tr;d?c)ev>CxVaPQvtuXS^KK^W`$4`iWD12NAOC!uf&V=N zGZCsC5xf||;do!)({{)47f;!Vd_I#JOQv)7Xx_7fG1oqPu;ArK(-~}esj+n6rh*C2 zwR__|2Yb4@d*j_bc1P079>iAHfdj<j-8PMMclA6K<xp|F*8yK2>zhego4)Y@Ec~}w zvCxuP@FakRylgBMK4i_ZJp>y$VGEi}aZvIbIi3g5YmI-KHErh7mxz@e>9H_YU7>u9 zZ{eXYGMB#8Cz&gIlv`C^Vvc8)ut-L}!hAP#iEEtsJo5zC6U^^%U+hrVf@Y?*O2x5} ze;q{{H2GOpd5gL9C7x@{ZFVT*zhZusxy+Z$Ss+=Vo+>Jyjr^}T+@Q&y5CyC)xL@n3 zCe42*YDf`_bYvy2{6N)W6LXstM1CvtE`#r6?l6~mJ<hzJ`QNzy9CGo=D6Eb}@RuUE z7r|eP;NL+`^L4PMa#dCEPK5k-Bls`a&fnQik?s6BLcTes{1&jL(!qNBu)kRzJ{7@_ zMQ|56&FeBhYPKpjfM@TJUuAAHzrg$!^XmSozVq>f(LM?7BaoZOWCr<|Q9WNAP5a5= zjBA`f>Q5h;q#v9rj3fgW(*E<gbO3>yEmTd>@L)irZjNl#4j_4daLOO5JKB8dY!)`b zgF)U)o^^Ss&V5az4vWUnP$B6hv%Yr7N#*@f@YA_b7|kXpv3br5Mqx5MO7(dzMoQtP zQ?<iWI4LD?+|9XOIyLC#Mj+({g+4i{g)()dI#H#bNc!W)-5`-pjrZjzasecL-}Qp$ zlIcv%6K1WNIOVV(Pj>a5s&;XXg_`P%`5-+yCEC6k)FZ6wC0tzTa7C)S00R?E$hz57 zVJgC>E*LS}&~?GZ{77yRt{>ETXyW-?G8LrH;{i62&boC&hiSm==kqOZV;JE^3*Jxi zt{^nV{9%I^G<kVO5t?Ma7v&%0HdU{1`%&b&ygcX0uRI$`be84Gug)(rC;RQ(rs_>@ zn{m>6g$i-quRO2JIIk=5P+s@@OXjBETN;0y+f==;@h3F?JB@!@<F~nO#(9r9<)?P4 zK!|-R!tJn!b7W3-NM86BgR?knXHN6#5Qudvb924+F&Dq0VjH}R2iloSJi_I<EnMt$ zvAh{izh+-wNBU!yikY`D&CZibB>W9DJ9<7R4eqecE1G>>zG!fff1SA*|GdWab$^e! zndc?VzCPcZnjL-r-;UtR8vhK>iK<3?Z&9Ij)a`F!ZsxO<In7It-)3&ce@K(p^M5o# zKB39$^U5&agMJUHki*|u=4Sl(?I<i}{BJTh<9v%b%}bASUgP?Fmza~^y5|FP@~iXr zH9MVJ{I@lEJ^$@|jxg<aFgNXgfjPym=WR^ma?g?bK;zw7JVoZF-`AO&erGj1`n=@a zB<mvYl6P4C5sZ`OEBuF=9X-$2nTwt69P1MEPqH21a{dx|Sp)pW7#3M~;eXNm>g$f* z@4`ZM^!xpe!5t+A_n1?Dba}a{gp2$ZUTpLEAaT*(5oG6Owr_JSe2n`Y8Yh$To;aj& zvNOqji2GC7AUTY6;Hi2{TArIp#shaUfH)p9lMo;FeTaK`>X3MM{E&1Zo=RoaFe!yc zzj*Z+f}?mMaq;N&e-|4qU@Gc!ihTz!D!Vz4s<-j%zZVBc#1R3mCm&LcVza6rz>54x z{&y=3PcY}@Ws2)!_>}>&p_k8MhipdaS9D>P)e+sBWV1(y*cSiaG`PesaX2_mZGOyD zrI$JW*(y;D(HDFI8>DZ>U*Jz9^4=18Q~y+ieh25B?CZtU@5jN-*6$8}+^2FT`~{%( zBVEy#^&3S-@ps{+mje4gtwU@}-t^kc9jV-6{X3jT`up%vyiEW1Av1G_2yT)B7W|-H XSH!Qt9oX1R|7HGvue=CyZR-CUpE*ig diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/controller_pid.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/controller_pid.o index 56584439328e8718ca291368ab87f316790ed281..fb33c6964c74a59799aa902984711f373758917c 100644 GIT binary patch delta 961 zcmZ`$&ubGw6n?YY#$-vhH9uP`Nj5gAQMOuX4VKbQETSSstr3Ju&9)WkLD5#l=pjje zcoUM2e?SX@ZSW$w7;rI{LjD5j!9yw@svuNFda=egyD0>r1M|(k?|tvRZ)PiMr8{?& zRPxdJ_5}yTf(x{?BMOCp6&}DrNQ7Id-j-j#Jm?i6zb=Em*aE$or?iv-=*#p|9gv4s z&@(f%lmyH@rX`S}Z{8VKc}~oM>J`~238j}EkjTu@lF?g+MD=-Gb))37m+JFN!|Gy$ z>Izl-0Pu3c33*L|d{uN6c$}1IYEmetG)p;E72y&LfU7D~eF8#$5%-jYwRk2aNI^N| zUyz#BtZY$vZPiJ20->0nC$jyZbCN)pzlwu7r@UM4RyLIJ?4X$gY_y3DGZrh}fjNa! zhuQ#g=l<6E2=^<x3qgw4#x|H97b17tkWLFwO5=Fkr9iql8c18Bh6H8HX!X~%_}cHW zvun@-`p)F=+SU=eyZdZ?wJhHHSRI)gO(tK@WJCDeIEs$}bQrc%J?w_SY^~-qUz4g! z?1#`n(##?HJn^5kM8;qL3qjNUi{csayoG#WS=$}*hOO9q<b#3V479Qy$wwjvj&Lj{ zrB~#@j5al`-J30n_V484DnaA8I`9mep9a3)hu_$T-(s4>*M3+qTewiw)X=SyU6oIe zUZ%*t_6v0lpV-x)xyiHSA$u$PdY&|B_{;9C)qVQEF>1>kuYYQ&jqDZTx!u4YYv7wi zGw}T9*<R<l&*R10EyGQMTVw^-X`9tyR&24at{6!$#XUrBFwMXf#FK0jahoZgAyQ!) u;x=3H4B1*OX5ARmEH3uP(`mb3XM!y1joEUNnSaElF}mW~i@18gZT|<6K+1Oj delta 811 zcmZ`%O=uHQ5T3W2#AHp<ki=|%Wb-3wo5EHUYe7Qu(%P!@Al4iNJtRFS9t2yk5D(32 zQuSuy>p@R8AZT(@a*#bdh|oe24?TKJ3Lb>ss<j6(&hA#&iv#oVX1;mf%+9{;@olv_ zN-oz@<$+BvOvWlyKNN*#)D25C0J&s<a=Es3b?QKX+Lj+U`Z?_()ir<#?E>W;%tHXU zwoLUrAh$ww>Vt`LFsmAzSOxV!U<)Ks>UbfiJ*K*;?SmXV&8k1JM35;jznD?ihAEHJ zxB>v{1qo^$G1OcPqCCcVi5BZ~uNOYm-Y&;rL~%Svc@gFb-i0)T3PQW+goKippqO{H zixqcF5ucq>ZcCKM@SK1|R3TVU@gGy4NKRFo2L34GQk};sUz-E`4mKv79h3p8vwwOM zU7TxI3^!xc>W}n_Fg*SX(<K4)61G9td#lb=Z`GADMl^iGPx=1!Y~$z6=|;!TJ_}0R zP&Cv4r%rk)Plh2{?Db@8IaGbgJmQeLh8b;;^0orp5c;<#vfs;T%F&u*7ROrG#7i#n zg}w6JAs^Y2M<%-_0xL)|QB0gQuvL}bkXG8eN5~HQ;FAX&0*a%B2!O*nn&@S9zdX=? z#10{ww6Q0VJxwkeHCJxgYDR1|d0T$emaqP&<GP_n-kE(jZFlW`zp^uZGTAd~eE3jI zGiDoWee0WX2*2@{h0l9-ycV;;?uI8xn$^P@LRr_u_=ybZX9dLjtd97eb<J};k`WG_ hY%wzBx#6;|yICVL>B0A7+CBCiqn)4?Jz$M+^e?ca#1jAj diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/crtp.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/crtp.o index 6578f168aa5e570fa95f161cdf92806e3fbc829a..e61e42c62711980cdcd58d4acbf6dd946689902d 100644 GIT binary patch literal 2368 zcmbuA&1(}u6u@7)RjY#5;z1B}m4az8OA--U^$;6usgx4ihzAeJb~|lCKDO*kHJ*$& z5riB(c<jxqH^Ea6Ui<^}CV2CzCy)Bx?we*h-GJbO&3o@R?_=j<C(rM#ERJO|pd|wz zVCZQI&_6!3OR-sk({Kv*o!ZySuJc7dF7($-X4({E`&fC(WZ#{!S<^S|f62G&p?~Oo z(%z4z6GUo<bktk(l>ktzr3!aydJxB7P*94Dr7%LHcz;AZES1Z*-0afoL$?}+?V#Z| zyY5yPxvC-DySbex+-kPbih@Q{i9qc}!kzbuxnjOB?-hz}){i<lwDL1E#Jz$`BZYkN z=BS1Vr#&BsUw_h~oYWHm;Eb4^gCn*~#31ctQJrx+9M2ZXD1Nm58H~;tefyM-aseOW zeR5FFCo2AR;F#ehX43a4zl6gXBff5AI&i}95_1;Sl(BAlCO4Q*az?T)0C$+X%ys-K z^Ss6D%uCF5ou|wz7JtpW&Ro}j$2>m#XlwqFc^@^2uKyWrn%5wvL;j8Vp2dGKe{b>M z%=ek=zVV0X1u)%%=}idyc6-AQS`wu4m4sTY9d66yd!&zYx!Y86MpekfAX4>Z>%p$r z74guT2t@OVs9+h9#2g|E?J#H^4SeKt<t3pOBO$82xMEU8a{P8vDiKw}NR=02v@W`v zMx&u?c9HxV%d#AHyZ8+YoG4CaU8t32x0Ni2UT?aZjjI=2UN6mcT-M;UmM__#GdR_m zWWQu^ihsp^#o!cA-%l)_eAZF^26$3MiEe01iJk&)(^o!t8&ZN7h2&6V!J9)@w0#dZ z&WrC+F9<sw(N((e|LKdEPPdA=MpUsxKPaCPb?~d_ufY{GDBr$O#tEi~jjv%0?SY*? z!GUkA8hXDpzK#Zk7Byh4^RL>Ref=IK^vSmS=Q*H`W2V^sZ{r~Cf5{9&`z>FA1Ll-R zNayQwaUU7A%Hw0ofcrl-A=-=&>9qgIpB%WygC{ZfEIxLB;`ZDT!GI=(;^>Bnd(f9% TI7czsF?5y>)VjgQw93I>t^)s$ literal 13384 zcmeHNU2Igx6+XM`0xb|s_$dU6?}FO`g2lKX;VOjdpYWrY)G-^yDoMTT^#xWeUbFWu zS}=hHr4kQSVgqVWng@sS02WesAT6Y!H6#yt;DHiK^N>oWDk@SV6$G@l6vsX1&N=pY zyxXK|pQ;^ccjkWc&3DdxcjoThy?glC#*M*10Hg%q*D!V@D8R9*v9|3uZI}U1K<tTp zbAPDyc7+xC1HFd3es^v-1U*PO83gFA1?X8a&AxmXVE5@DMC-u5Qvb%;=CT`;XNJq{ zD+&1iq9x__<;r|uS>31ML#+TqVXOf{&jBo1R5xYGqA<Sd=2?p@eAQlh=TNvDUInbJ z+3@Oc*VVJ*<G=66f4D7hZZ^h$7z*@YB0Z0{2hYvH<M*)rtHsds&jm2_W*hXp6SRj0 zLbLidz}&y(Ll6y5v4<?!aN8akS^JmCwKXBg-wZ<j_#NcDwy@!ofdlP>d4P*FKk6s! zNL#RnG#2OD2iveOj5TTGgZ5=8gPHjtTz-FK<V`)+)h|Y(b|BwOI&jcFLG_<TM!r4V z^_$WBXJNjNK7<}u%YPr{PIHK1-W8a$9e}9HZ+2hr>-G@oRFuJkJmSI$j7*GmA7c?$ zV#j?SX7}Ma@#lXh1j{MEJ712h>7AtJ(K`t)AH#Xv!LeiK`?urrrCei28*0$YwU}3P zpe%nAX5??uxuEkvF=<@{@D+O<hVF(iCa#eN^qIW2u^pVRd?60<yMG#--$NX1kMe@m zieq7n*wM0@hudn;4R>7|w-zWz8V_LC$Ql{$8lP_*b9#hx4acCz%6WqWc>W}=#5_7( z#iF^%oZL3dCx~;y`NR&a87vlmxa-O|f7&>njqw2EJ)Q+ak3)ezJYN^HLAXdU?u6#_ zkv_({89U$&QVi06Jj)&$?)uQ5<AfY>9};iQmm}}dyv_d8+<#9ycf|WI^E>{v^PBM% z`EmbO<(KgN3-r-`evIcWhCcoy6kHCu?BD=;c#Az82+dti9=ZpzzJGUcodt29(LNpZ zb9)`GnZkaaE?4<p94_qVHSWJ__=(!xW7j~n9|Jfyx=vXD&&fKJ{ZnDX-s?bn7`p3l zebaudiv@dXbJienN7w6A7<w3jKD?G(j0NqQiX80SjC-8o(Y1-MQ@9>g%!gBHt*HHA zu7zt)skuGC+|9nz-1k?W*MAuQ_}7ZR;NQgOK8Y`W25>K^&lNR4!u?p~_K@vgk2l-~ zycU?B2cx`c_D~FY_t8TLR@|oR#yEdRKQEx~2wn@1_?r3VF#2iXwfqRKyTd_v5VoM_ z2XNvo8XrgAi6EXA+?)4t50l@djWMCVIoh-`+M?>_7KlVv?Mb(1Q;xgJ%_LSOGG1pS zfxNw0C+oP|JJT6&OZzL<`t{cHFE%!sI6x<fV(DD@jGH{*SWmCFC`9Yl+LqRa+GuU- zwk<z?7W+w<c$r*t+;adtu3azP*(#kxD3y`}B?n3llpH8IP;#K;K*@oU10@Ga4wM`y zIZ$$-<Uq-Rk^}!o4&d*31q=S}TCfzu^99)mZmO^Up|y0=^DkP_bUKyT6;F0pJJK1; z+vQlbD?2mk9my27GKpPD&q;XMjAPYAs#jK5t*(izuC|uOGkaEIt7_RY!Xv9K>RDY? zy|!3Dg$J<0$2}v3SRtU^i6sP~i69~&R5HsHADE~!74e{^uXq6X%*w~hSt!SK1>@a( z+|TuL#+x|AS;naf!8f!c)l_yA!zbpy4u=J_dEs*?zdXbEJU-5IO~0WM|CE9Mi1B%x zr_A>y#x2Hmr$R7^RmLin|3v&JzRnnKbMpY>a-5$wrWJz8V+Y()`V;Y=`#NK|<o^rC z<#?&47=mwVN2;mxC*r^Kb;j_RHZlaXTE>@m@le)?-gC7G{z(!1k45l57s2l%{v@qi z-ry(km<l~OEtJo6q!z;GBThQKtRtsoG2<5)Z}-&!))dj%z<i6hq~!Ag<NXG{i}4sQ z^)sx0i1BjX8kLNnLcCD^?=s(JzQz1&qR;q2#(&TFfPvo?KCf5WZ&dz{c%isK^u_m$ z`IgT{jPZWP>A{v?_(@4+4m#4E8?zk=$ac2lqm6A|+;jcM9nHCD+}-UrqpDfi4zAy= zo~}S5o=UaF6T4k}9P$D^aDk+|r6cJ<+TFI_^&g9<ktmwjU6<Xl!^voUDuCXXN_Om~ zd>W~4ZB3<jDi!eKZ*sh7GO@cpo$c^I1>EFxIGJQ(o72$_TdSk6k5X=MQt|yvXm%1# za-ZYR!cT47xcZDkPjh^AZj&!j$Mr@>kfNGg+;yFdw=tefDSwo76Hd)hbPlGFx>P!$ z+#3hK6i0t32+n3>#&M!5AvMN@tUBE4xNdx>;}SdBv6JKNOuC+vX~Jh(^>sc(^VZ^z z9qPed%x>JQn;n8Ehb?Y>x}yU>Hl23X^L*<8<odk;*V`glGgvR=_AJDCtN4h;_#6YT zV*EP>-o*GK1Am)wQ(yL@sefMM&*e5%7r0G)9Uo+z=0%^KQfxe?Lb&C()Ehnv_6y-* z4S$(&%2U^GXWWdN()hY>p2pX4`XdJwin~}f{rB@4ZfQ9Exq^zB=LZ^Y`3&{;k%osg zd>UV0P5;XoH~n9#@t@RmR%m=3uVS3?tkn2xG#zTneakux|CYvYV4U*N@g@z|by^sw zxZl-uUS^!;OFHs-9n)}XcJr8Bj7wbMr!-vWA7tE&E1z%TvxV`goMHZ4Jf`&^_y>#& z-zVc+KjY?k!T)RcMdnq`13ooyxi9%l(;**(KVaa(zsESuOE3!YxyIMmGv0Li#XRpT z7&qrt#ke`IrXqN|roUK)^51iszCN#m25$41yr!@7Uo&vw|BP|dhf{{W`1!VhH*wrv zLtpr33|#o<88_oz*YtJ&Z)iF?j{n>6i|KP2lSp6pa~|X7x>{)9;*Z6+>=&6=rGX27 z1>@$t)*1Su^R$7BKenMS{00LTek0>%+?1xzP2aChO-IL17QxRjPWqOwpx!QOxbE}E zjGI1RH*lM^ZZK~8e9ORv{~6=veD4|h;@js2F23D2^o9S(z=i(><7QmBzn1HOd>>rM z_r-FbAh^Xi>8xZAsM^f9=tx&1<K{Zg8+_64X55T>l5vWw-#?tuboA@SSp#q3gw8W= zp05iAF8oW3o4)lM`r`jb1}^@8Z0HOBx`7M-7UO1I;O`USv-nodxar$$#!cTUH67iz zr3NlOtYF;qt;)cKzm9P;fBD{T?ym+TuK2Lo&==nt4P5xqB5`AyK5Yf@t&?%nH&4^4 zmc@*9PServKM!g;I^J7^f2IikdJ+DuBK&)d(|OV3%1<dYuW>lfh5jN>xZFocO*r35 z_)PKJ#OG-`I$zhJb(LeDrSS>R^Re8+kUpIk8NZJE2`BzBKDITS_|!*5&cE=x6$}t@ z_wVuIZCHC5Rqv8k2EVUHJSXQt1iyjDA=2i$5Xq$Jfat3u>mZUy>`^e0{T>_^!S9&y z6mki~Z_5$-Qit61o;?nJNB$oa3pH@+vfW1&ZEnpT`{~O^<U9#+0XE1VTL7;6`NJ;8 zKk!gRam05yuis;wZ&P?Q{;}7HD;=bvmlb$Gn&$Wx9v?OaNPN*)jSZscdyo2L{9AOO z6&WwGHuh25j6cZn`}HqJ$dmEd^vhO!FEswrQ>wp8Rip3b_|4c;$bV~<8WQ7?<Uge( z<Hi3r#0tf~$MIv>uNN6F*elp56hF`LWq(k7`ju10OZ*gK6yKcZW?EQSwySFNow!u= zTE8x+UVyVaevp#GG96#^JBJycax%{yLeOi`JB~5LC9diPn2C)-<I8zMSs`+5j{g@{ CM>$vk diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/crtp_commander_high_level.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/crtp_commander_high_level.o index d7f6d5a7c7e32f40a1b7c1b54addb891bac0697a..833d1218d84e3c000670fee0f87d86b68e8fe4a0 100644 GIT binary patch literal 3288 zcmc(hJ!}&(6vrLHHv@$Ufe?o%5F~m^A|bUf5L6&k6jVq6A&}A|akzs^F1m9|%R<?Z zSUNMYF|e?~*aZoRg#~67MkHVb3EsQBm$*($84y^y^Yich?f2~1zC1WHeRf?YBe-P5 zOVMvJ6=K)czFkVqlGr8?E?r*9);{cWvhVTH?f=m>^I5C?uk*F#0}FW)A3vOoS}m{L zka4=o^D1gK!I}?&L7k|mQ!_=tAExTT*P%g_5*uH#=tX&Q^0<>LU%cW}qbRKVUeI=$ zQS2yRI;X}uanuY#u;RKOC|Or?v2-Tf;#e_Xm~ab4C+EejF|hJSjv#jn4tfgt;xSvm zF2}vNUVQyIOqCtFQ-#Qib;IPqvjco@N`~!t9B2K2-bsm#55_$J`izzj_dHIV+g#)D zS+N1DRmDkLgZvWkjHaJWb=_B1Y|>g?6Zg_iZQVALqC<Ry+MLg0;*P<e6VDs`E%B1U zKNFuZ_z&W<2Hy=o3Fe7;Vc~pE5MN4ZpG)G)#Ccvz#Ge}c8Sxhee@%RaILG}+{GGwS z6aQ%NgRm7a|1SnVPaIrn;qhbQBL;s$+%fnH@jP*!?<e9VgO9-0-yy#JWStnH#Okr? z)arca)coMKUkl~D4BfgIT@a%U(U47VE>zQS0R`>bS7jL01GUJw>fM!aMfGs4*70Jm zm8`m?f@G>)j-$Dbz;L}A?i>W0##mGBK-pYL1+Kh~Y*_qN8HN?*DQWSSrK(8PiGsEg z0fd=^1ZKSYU1<wQ6S53P-s|4I-wUn<%I~eo@JZu>S_VPaAC6$p1lP?nemSZ}7S~i# zjlDZ?gGce=Y1s_g)|H1<k5yl68LvCWnzFv&f^1cS`?jC+S`43;zSt7<vh*5jiu9SD zg{_hJFjd8q4`fnn$rh|adQkY>;9sSUbab$C$Y##RDyMP$>hL)q*Eo)|i`pfP>tCrE zjicV7ws4chmhx^vt>SL&v!&#M5^lp&o^Wp^iE!fx8>lR}<It3$=ccFB)&EJjcne54 zCV!*sfkE&J($@;dE#V8wIdp1;*NxGBFi@he1^OOQKmI+CVd3@dwuCqg25QXy%SK$* zoA@X=kQG@#HTN$Vob%yvO5jJ^jQ@rNv*6PU_h)tj44hMm0oA!JU1OQr*bn~|aDU!U z6<`=D5074Q@O{8?qg(afoVQ++w5LJi5y1tT7^brw9y302bMAn88)DROa@<q{uO09h QlGOEz=6{ogRGa;O0m70LZvX%Q literal 11008 zcmds7eQaFSl|OH0Vw=QE(l}oY!FkT7W8%RvPGwh>@@yxu(;6`Gw55gB%y|6lnd0$G z-aLatpmCt>R!w&m1KLGe1a8S{asFcWj}l9n;sm5p!L|{lRsX286B8CU%eHO<N=C&^ z&w1}$&&l(=F4bza(q8G!z4!OdJ>U1d`<{LLK+nN|rh#f2yaJ_}LIK8imd1uNG~ibF zD}WHJoC!vMu~`rPoUXrgF4sCdHi1=G|H4LvFC6>f)Ity@uC9RM)gYV!FxpW3Gn<j_ zJV2xd#t#>QH4Rr+7{!HS7ha-u8jL@M8oy0+bZMt9zFi54=lgdUZRfYo{a%Nm=h4Pf z?{A3JzHju`J`sSuTfxYihmCV}022eNjdOYoCiGBy<KXv=b6Zv!dE$fe8-mC;fEUU@ z{;mwK{O!o=MMJOsuNybk|G&|{Pn%kUK6^R<6S4lzwn+{4qEAlYH9@|K^}D@}@pvHs z)5j~IcziWX$NGb9$1NORf$6J#?Ncg7i}|8>pudsN8s#sFVJYUWpC=E#aCm0opRL%f zMt&KtJB_k6*jcM$l4v&aDlYvUMt*3WQ5>u_icnQoOZo9PAt*k%3i98|Lh*??$dfLU z02JFbN}q*eXWe{5dnw;O3~HEjPQ0J`=z+l0T9o?(^uaIC-fOo(@!D3+u^)Ljc?Otg zbHVjzD9;MPb!X}@*I+}u7BJ6<rhxaTr~HLmAfj|vdec4PKg0ecx`GA~W&1eVPBuS@ zwmyM2o<JMN(Z<(SqaA4Hg)5LhkG`KlpHBuLFXa_N5P@HP^YCQPOV)cU?{0iI2>-eT zZ9D!Qm<Hsj!_3>?L)o*H_cSJ!S593%X5?cXP<+1+_r}*CpQzGnJMj9CsFAP3ejKm& z`i$w*DCga%F+KEo$j|OHirZJgbfNRW^%&}O`7Wcl1^u2_9&C(nfqefKD8?F~IQUh_ z4>Utj$5?Egb93XP2Rf#%-A4QP4QC&d|HvP&;676E35JZekT!mJmTEyYOte=)+mqFs z?&=Id8|{6{pE}Gzsu_h&n7Dy;qfn!ryODslOG9|QsGa-IKi>EUm4_<d9NJE3Bih+M zq-WZKpd}p?{oG1esKPx?Ia;#`R%4DFR&l+=b!l#;vEZ!@l-HC`L`zqIYZKL@t(eaj zFmI@S7??MzKIH&fVpxN!cImZLpF-_=ZN;i^E!7xRr#@+oBAt}&%AWtuUq2N-_&>G3 zwf=v_{>5A=6aQ1fcGq98PEo9Bjf(dPjJJawJ74bk<JL&GzCBZJzst1?$EKb7Gq*FC zK7{d2;&tWDP`Uy8lX!h_2P{-$f0gPn=N&x*l`i-wk2pDpwRUc2XZp&W`_muXK{5Z) zO}bGnTZcLKGu-c^SZhAGqq_0e4>`4PF)uIS9;19L1lOL~g>~%!=H#wVo3*>z-C9Pq z=~4h9+c6&p@VXRS(-6d-=nIuSjk6DZg6AgcN&CK>t}_86AHNWsQ2dGaEXo*MZA_Dl z#1&)OtT2jt6V?*TDDJ4jx|6_K^(YiCo$P5GxUlkiqC&&k=03as9qS07&o*y^Bi-mH z4ehVP{Zuy@ng~4h_|wLW{-&OcwQdGDQmA~vIfGDa)LF!h|0`~Mw(|bRIH>(kKK%^x z|DqEYx5oExJoM--C~NVYqU_yDG5N6*lWU3K)OytAI>thKF*FhT`r}X6%-r>63)Gy{ zletz}yEz0$@L;wWTc=hgI;Z9YpYaN#O<x8rM0@^^HzI&F;?)2gslj>)%dmDJ=B+<L ztUpy4+W^Xc4P)H_MzN-|VghsMObp|FVvBLM9ki2GpN`d5aonq(*7857guTaa#pnET ztgocEQ859W<9_F)YpCz57z3{kA=H7Mo20|*tb_L2vWfZ-<WHauPofU{@EJ0`(P-O; z&z61&oYZ@vjh?Gps-fsSTXR}|T>x4N_`IG=XcMD2rnr-Cm)C!xQLAci1gxR&Vt#bA zZm+Ft-Bt^&TWhs3EgyJH%fq;qC)(NI+6HZA*`h7~Mmd9genUOxAMqyN5C$vS8?_qb ziTp1!U*bu;W8cvl<Le+ljq50H)J6GM$2pk5{tb+22<`p`=HWLm4|ia!mu-6dXOp16 z`AvY6-%9GOl!M>H=iB#nIQ!xT_c;d`Q_4$#CvM75)NAo9Lo(kDY7H7_EB1wqBPp&^ zwC++caAr0bY*;w<>QoTrQ$0&y>|=(0l5Epa<^tC<r91VcyOe=vhz3CZn?3xAZvkZx z-&sco+G|F!&e-bk$36Bt;;;6ZlHuh~d{nKabG*uv4)hnDv51F(dFMH2twA04(UlzT z%%s!tkpa`fDZs;aW^j=DVZ^Y{*_mwAON2NX`RCdRpPM`WLVVnZ9=bX^KdaYw-Sb5~ zlF1AwlJV4tKA5p|J8A0ejae%*m>R~Bl}M&+GhvTfrrs8AZftJa(-z*-tk=h_bR&+M zcI_fOyho=ydzzZ*)c$80)<g)w?{1VM31R^%*Mfi<RHg-ylegXO089DkhzF2=%()LR z!~HJo3D<dv!tZ4K)C!kSNirCpXS~Y24fitMTkQf0r&$p2ZNk(3+L`;|OYMyzy(avi z^m&AFHCMgMU(Fn0&d=XD^d(%4o?=|-&1S&gGrqxDUGm%WjQ^5x<?(-Fyui5PgNGW_ zKLqoPQ}LwsFL)7N&kPPaDDDqbjPNYuI^&g$pJM!F#;FTJg_yZR*AGkaALDIJ(CcDl z5R?~6pvz||e$nAm!egZ+sLygSbBFI?w;Cm@rdD2Id==kN_-`54J@`kAH+k?sFm5oe z;(IHKB)PqetGH}HT*>5HPPf|!|Ev$*<%5642TveQ`V_FIcE8)f*L~=p@xkds3-K}V z;Z9B2@<Si`pD=wd(~r5!;5Uq4Wc*p2Q(J{|#nVOH-z`4)ULSlP;-qJm1EMptdl)~( zcoXBpjL$H>oAJM8e4g>Q7=K04b4gKr@MDrAcb;)YUsUwGH5C8#Sb9j$dB$VRznSsg zN*9Q+f9^)SoPX~3!IRAAWlr!`=KmDq^NhEke$>wT@c9YipMu}tQ2RtFf$!~V=rZ8n zkA3jl(U0Zy-|K^a!3Y1U4{jq){%qpsMK9~~kBpCdo+Ga@KFRogrvEkK<@BUHApZER z!fD-1zZT<7c#Lu7X9Mwad>~=j*=RzYWunQ{P%=7fK5Pz$6R>Rz?D#__o@|<d&Na=D z#NT1_ZZq9w+I^`<%@Xis3(pIs>0vWI0NVy&z#NQ^4%<DrE;TarC385FNZCgf9C5iX z!bjteKsJ+uEJ_=}lT|8rXe4C=Y6IrO;nwDsR<N!3*YI4Dv5rOu%v{1sW$jdEBnN3T zz26*!XfzwQ;_2K?XRkyiHwd}Z$RG@+<6}5HV%dW*cHgKuYIa&?+&25{xSdKk^17_d zXqIpGndx{onXyb#6h?DqB9cm*IXj-tIyy$#JxtzZqSC2EpNU66G9gM%b3D9wSnNjs z_K<rW!%%57<ghuE%GsvX?KszRm!`;Y3Qn1&xjsByW=$57%0=n4N%Qjb5p#H$3^aZ2 zQ!Gt8n@Nq>uI$99Wtk&(bSM)aMxR8<=TY<F_;3`j6pJO9Kw5U9lD+Z7L#Cg;9AzKr zeD^CDdLQ-OB>8g6PA(=&c}mJMA0~9`6LRp^gxv1Kzbg~TxXv5OL~S{Y4qBPC&#FVY z$YMHU_NGRBV~Fvy>=H3VyL#^JXzz*Md+=c2fk-sc-qCX)TG|{bGZ%G}3$iIQVLp<| znY7EZmYK_$1JU6OZcisgF_|q}-YRV{vD68^g?Ve?YPrytS}YcFiI0yjT>FKI<zrkT zz$)aFpz?H1Jt`4XeMn@F`pBkgC1}fYl)*ZPiJwa<SKt=G*tr1LVVnEgute|RF?G)g zT>R+^CIw#4W9rWGxCZ%P$zN=5@aT3Aev$FD9(;~*(udxC78}l~5sok1i){_#Uj8kD zUfT7bz@=U4yg>Y=U1Ln|wd>oAd*!Ngzt^spgxot8wa51rflIsI@!|gg<6eE{8TZQl zSkP}2a`C0oX+$sa5aZ;BMnPXK@UXzwFz)q(I`4Y*+%M$HJn3P4Bg$<O{F6eijMo_B zUjC2y@SkDatLN*ClU(Wlc_02C`tT3o`HdR+P3l=CaG6)T1%8*i)cI`@xOxYr8@&RT zdg33@oaT-DgMwcA^Et-7emE`YrQC}?{6ic(FP|9W<OlhwrJB$8gv<TdDsbty&k0=m zt($Rg+<O@J`XR!&SI?{u{dXBBJ!SnlEpX}oYJLw{Vwb>gvP<AM*~R!0yBJ?$7voFp z@}d7O<D{poKc@vQ?fO{YJKPj=em7OR6XGN7(i!*azm0LP{<{SqnJ0$8r9R&lxYXwy z<6gNljC<u?6nu6HyWSDFjLUU_%YCF*mHa>-T2*TmxYYka#=Y@6E$9u!1p9N0FR_bp zuU#8%aTj~@u$yr&pB~1&e9j6!(m&?}UN7`~L-6ku_(jIsFi-Xid|vQ5An?#~cjDD& z72{;rK|x<HaOvmI30&%L2wdvl!#Mdz>K|d;tN(L?PnXbVl5wy8Z~5TA5`4M^pUVP2 zB=GA3|GdEW^Lw~AzTJ#_^-<r8>3P>9_`ELoNI$&AxYrNwFivr~NAUTOapHfs!0Y)v z-|OeyjC=XFFz)3aVVwBWH*M9Df?megX58zaF~+_Ac}DQRPcg^7ipTi(W#{Om{J6@4 ztMBU@Jh=CJJn>;yIh4AfCtUGWwh%o%iq)A(eJ@dblsrT5A$rw%d7$WZbt9ZRnzrNp z5YE|_+b7k?GKb?~+Z?kYJP^0z5bn?AAZ%r5LgahGtvDqj2f-2E4C9v*e0Oqj=Nm^@ z{&^{kFIj1PXIJ9?r#;z$t`T3#U5<v^!LuAso-X=T&2Pg2`P5K=>gfiydJYnGBuC|e z@;5z;2$#ObDg2V<Dtf}Gsrb1wfZaGC8t?i7uUF@2MepUe2XB!4W<|igT2J?7Q|oCB zHLAho^xuI0+DJ`zeoH@Uy+RBel=ELbKcu^vko;GHms+p<M}M~{C%={D$MC*vYQ4hl z$3Z#yS(bl_2}wS!RqK`fEMg?T2`|~6W%&<C5XVGIP4@gs;NIZh>%9JDK0i=6>+tf* or^lf;_Qc|)we$;cAD=tjSxK&%e+mcX)~mzWQANnT(p$lQ0$+z%<NyEw diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/crtp_commander_rpyt.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/crtp_commander_rpyt.o index 0f500c388a4ac10fecb59eb1ba890c0498d98b3d..072de0ab34d86f65dc9483029fffcd77d9863864 100644 GIT binary patch delta 644 zcmZpW?~t3IA;H1J00$0WmIDJ112@CQh6gN@4OrPG*RcvsP5{!=SS2Q>LD?+)LX!`$ zCNPRmR%Gi3%Wh)};;dnUm~?t_A-g!^GcfrYOnv~7lNYc{u%s}kR7~E(K4Eeahm~=1 zesLN@ab{i`Lt=4pYEg+>VrCA+2oVUyAkE0YAP!}ND4EFzIm8)tCVvEyHXu^c0V*pD zRLKHmgD8*5ik#w%6_W#j<Q5Pq`35R03RKCAq>^WHBT&`@C<+1~bC6{NCT|3qPy<rK zxCBJjpMk0bxlID12~0jf5|>00Pk;ss$YfR|@f0+14X9iOR2<|^Wc4`^aWe*(1WZE- zR0GICQb-nXK-r8SgC?)#5@%$ce3VNcNPY#As@x!UD41*olUu>$Q!pvYa~kOFhdkzt z29qUu?OFGLYyrlj@Z<ts4W=_plV|bTF<oGqe2dqPv0$<!pFN|-<VYatF?lARJ?9E& hTy#u+$Y;)Jzz%WB@5zb$@{=9-C74!lPmbbO0|0iBWN-ig delta 802 zcmb7@&r1S96vt=WU#_ke_G2~6w&>s?s8e1lJ#{Lmi0BZMP{M-!(g+Vm9=&C}bD+>6 zqClY_$U~kxb*MuSBy{Kx=-8o|@fnM^2KM{jeC9iE-_EebNMX1XT`L&mZzM#PAO`Ug zB9pF1Y2$U+l3w`p-+3+ZA;Z3^!m1JgO9{fFqQWeTyGn)*KvOvt<Van%-Pk~t#Q>qC z8|Q6)hurGm56CAwcmsI?dEV7Zn((Ze^oJ`<YC$<i#<pNyEA{SWQzUEerbuchnPcfe z<}d|s+Vo5^o88VF&L!<MAuCudObH2N&ciz9J&a2Zo`$5`q<NtQICGn!BChr`r|fXv zLxVZLg^t6LZqj+7MHtb|P>H$u;Jcjl>%#NN^~At0<h}K`>_ROEHyyl;ocF9c_(cbg z;@Tzhz7GF&i$_R%p}pZ2H}HlAVaQ{K_-oo1Wno#$%fW(Yf~s&V^hW5rP@k9c8KFBu z&%IBy4z>}amrya{>?)f^++|2G>YLTO@o>t}kW47}ELw$%FHXzQWXjIcAJ@O|*zdvi a$2?`N)rUsm%0H!B_$O>aP40oZ-}nXRIeIYw diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/crtp_localization_service.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/crtp_localization_service.o index a03ebd7e6f00533fc3ca159d6f1349aea03052b7..2293d9f82a6fc22b22aeda6377923fb040ce1b4f 100644 GIT binary patch literal 4192 zcmd5<J!~9B6rRf&2;nCNQCQ+{AQm_hUfmgx9D>kA2~Lm<F>#QLk+`haYwsy{xAyKh zIB7VbL4v}922rJSNtYB9?noIS0WN6}ZRqIWz1jE0b91|eMZ-vY?|t8V?`L+`GwV;^ zo}W8Xt0|0{x}^>fSf%u%2Y$=CE%k&NS9|sLug~lHFSyF^kLKIc$9_BUCWm#?XfeB{ zRNTK5_SfS@lf_|gZsFA#o0IwZ<V=6PD>EwIHVbLKXjad~6h-sf=KZbE+$VCAZnTl~ ze*R@;I?+|uJM+toxA}+0^}?tdVmD=CQzkZLV)K(iKy}+2X|9$;|Djl$lzdwUBEp}^ zyl)=z3BiZu2Nij$>b_i||G)8vUDt~h>pE<nsfs*R{7V)3D!!^8b^h$xH}ur`_dd{< z)3h5UVW+Rx(oCBq)@P<SvUIJ}B`=GTj)^0)mBsp0Ff%>VXr2n1GkPk_deh`JPM%~w zXlkBmHfCP0Xi#YW8y{1D{Zpo@m+k;c)zy(QIq~%o{#nbE?IfIMY(%duQ^k+gJwf`K z(+?t>!UMw=`A7SF%jyq!RJtfUFjm5wO3hg@_|JtuN|p!Sn{UWxeZ#U!JtdY+T|MBS z!qwJ{@?Q~ObM)B9SYB77yNBk968?K)YYx9}b;VCzJ?x;u)z*yiyTsQV{e?nqf9vWI z2NkZiW|Y50e9h7C6mt7pSC2WUaDO86Bt>B0`Ti{YxJ-cmQ+Vz1D$0yKIKpn{Mrb-| zzn#a~wN4ZVk(%6AldIlQGjtH~>2h&xKFrNR7+sAG9b4f_H=ggTCnia^@_6V7vvclo z*G)qTDNdAFwdwp?&)YaW1j?B<gqBIW5oTd8$B|d4-syLYoUDs+f7O<nvqg$|CcWO| zb|}2B{0Z<Nk+)?+iv_<Y81FUne2?*7&wBbhf?E#H`qu<6I6T+AD|pG_S&zJl!?S*0 zu;0JXN{fU32ZH_n5sy01e<}KwSgaSHL4N-`qVxM77d~<FaR1*4-f(zc?}Xri!?XUT zVDyE4o)I4T(EqORh=X1W|AScQfp0rJ_cJN@j>B_53xbb&{1w64;}gMC4$t{9X2n52 zxG#Qw=(VSZ&d-mX-OrEsmXnA3!G4eRp`V86mK;6j#u^fb=ljzVjCF7x^ukjEnMZ!q zQ$c>cXTlY-CM#?L&(Id3g4NK3Dp<*L6=W#`RyKoKf^jztXfFw{l^ig#oA|`C1ldi6 zLhZMC5T(6d+&9wUe=|>0I4#}oEpDckfJv7mf84__5axLI-mzqre`w&j7wF)50Q2`P zYy5aTmvaz`_4B<#JlDtnCy*ol4-jGz&oMk&bd~kLB!X=gIRo*aPLnf6R|^EJ2=@d( zPL{tK5I-UOC9-Ap?@IlB(ZL`d_+4_!>hFngAbGexe}y0(^&{fS>hH=Q+69_-2janf zOio$-*0DlyMTA_Rzfus7`dh@6)xRh8cO)JL@xc6?%j(~h`u9Z0_4(@t@u>d=aa_Ma zmpcaXLVo0u<jd_GveN31@^^`!5PO_vpQFpK&-X+mL-Bv}CPjnyA9r|={>Lwm-;qzb Luiaqs{rG<YxZN~H literal 8784 zcmd5?eQaCR6+h1oX_l6dx}QKvUXs#=4x2U$P(!CZCrv*@RZ_<T2Ah%>=cTsd#PRbB zBs3#Vi%?mrQPXH36-_NnS`+P$3aLP~WCR!z6G$tx>yU;-+QNt!e^5FEkqFs2@12|6 zzSvAi`(w9yKKK0YxxaJn=R0;f(6DQpM^Qi&1zv`EO`rg0Zkn%ac2xr(EQOhUe;k?d zLiS3NGV*UPY*@AheEaJf&*~oVO|F7zfJ_+8hs)Q1+2Vo7@MEP-dSU47etcAJQ`Ug5 zUOg0URWjk(0q@A<8<4#eg}#e#L-4|1AvilwFhU$xnnEKp``$b;;cY&zVBagVv#X#0 zt|Pr%_5O{X@2k)3J0-_I3I$paIeg^>keURDlovs&<r;{n9;kKvzis=^c(h<<cDD9N zu@)Stgp^hWk)mrMGEf4kV>hAnLFxkP@Jna>mnl|&!<kBL%!9HCAiEaFFuM;<dqEqY zJfLJhio)srt=ib&^V*mOFdi*|apXDOQtb7&J^}vL5^Y4Ugz<|{725NGe8VmKp-+zM z%ZEH8FRgtteBaZ*GbzTE{VyFYUk$0(zHK?X5|n%HD7bI&`E_+?pIi(P?Wq&tWf;p> zQSS%_cX+rMvS|-wzrtq)#`ZPFG+hPLL99=$zoxSY)|V{;SbnMymJXLemi&L{xxM35 z8TfV<KqTXv=)K@wHhQ3DqIZ9Iq8FgDjN-rK(Z*Y`9xV<9LnvW&by*!g75KCigI_OE z{1oc|Ku5*QY=p)+>0Lc4{LuJm+|xKeG<KRZ@=XtoU&K)K&1{6`;>(BXM!t&Hk4#r- z(^KmkI%oDdYc{YBQn<E}fdHhAU!IMWmqIFza<E2w1-TC6V~^<xT&sa%NDY3DHn<OV zqVyEOo<SdEGbLKEu3tMsz6U*8Un}n0OStbRy~{_B6hrWU4}uj1D}5E<*)ZsVKC&~B zk7DX}_Uj(q%D(qn!^>X)@+iMJ_l5rM$6u6J!)54y?I@^9(_cQDjf8M*FxEY^p3&cC z!Y};u_ofF9hc6DCFagg?51y4z*Tc*PT$91OAWQ2wT!L%IYk8{h*il-uIJWP==LfiM z_BwcAydnesswFT^u?+_x`>JR8zhDVO4&eIXxy@#H{b<dqib6pJWd_$rLs_?aLz%r! zC;=ZG*Xw|(z2e1lsJ1}%BQK1$;(n<t@cLC1#vkr4Yx>aR>1a{Gr^70rsz8MJqW#59 z6-Bq$dmsc*TcK5yRV`7<2iL%O9gh3)Qh2wy05(;8I~#%0Kv^%wb-wViv#`0UjN+a| z{UYuwB?{R)VC7I9`cw*>b2Q<@GlF}?^HgZWvuKgO;F-D++BZtMHvQ2vi$*SNr+dlS zKX3s0UUkmqa1qKuoDZ5yItOTT7|&`}EgJCGBfmJOcsHHC`LO1veVKVt8w;V|{bp#) z@Ll6?!F`%}F*Ft}T;y;4b!ep3Q|NE|jpJW0Tj-zm@2B57`-ArEr|Y#D+Or=cM)%pw zzCStl(_)wwakZ3$f|>%i(-<z|d@C4d1;#mnF}4;fLBdt6x0EQsD~q-1nSHO@cb3C9 zK6l>{AFcOt+)q=>V5Ue@%PLAk!JjOL)Iq$fX%1RehJwcwsMUR;U`wTvtt^10RsD}0 z(I+Z~>ad>z%1|?&quM19tS*4@R-Y0)h-*yeaB7)0GqdjvzOU``Wygu}Wm|7??!`}V z&h@9YzPhSIVZ3YS&W`@Hb9M%h&&?(7dS^V&`-jfS3LMY#7<2uxQ1FdKP)ldw8BZo$ zH=$&|_IgHFLgu|y1$Q15@2V?aWt8r>>+u|_Z>vLU5e!Y?nTp_8ii))H9XOuJ8g2Zm z=W#CtReRqli&hSuFNExeC2(0Sg+66=HWFNX{m^loZ=Cb@PN9GD(^q``(5csz?69Ze zX!Uj4c)ED`P|+nAYeBxW#CN<<;#=$R9mjj+^~yuxdOYKk-W8)S;JqU5l;e1(EWG1r zp5Huy^SYew8S#!R{(IGyG3&_Ph(jQ7TW7MZCt;*-OPkT#qNdf|oJdCXMEp_RiYL38 z(}wwQJZc1@WDQ{IU3-n4U2R6My5+~}?z(XEz1y0@q21dXnwod+Zf*?K-_sC5JLG6G z9|kbG!qlV5G7Y_RTjP&vY!<?I#X?<s6Wjtuuhp1LH(7044eW*Oz1E%{-I@c^R?-g4 zCY|Gd5UhB#gY2dD2T8}5j9uuWrShmFAjJ(SZb)%M>Ji5P{Wf<e)9?V>|BR(gignwM zFhYHh+uZ`+hdIml#WOis^7~z%$Nv8f|Gwj@%rma<%Tt|)Cm+5pk9|HoUp%nAzWy$? zdi(C5s*z+e5sm5bF10;rs#eTUL;h|v*&a_|&5Xw4mJzjjOhXL@YWy`DHw6QmYSe1o z?DS)8<1M!k9@wN(%chMrblZPN!FK?r3zuhenRs(%^Z;J`m#cV@$z7cEpS)aMR8&0@ ze}<cD8J}SNIf>E>*DyLSLUuJDzA(<MXs<}|3;I2b3tdQuUug4w|6$wD<IB0Jneo-E zi+vMgTw@&b1G~^Qqu{*Nu`Xr`b0r(Eci~SkzSV_O(m^~8F8l=JI~Z44o@AWjq9Xjh zW7i9y+eQIYmL$ATC}~dBnV*IDIc!!WdvV`VFE121ouyBQXCZzGZ4}A=eW{NZiY3jd zIy?*U%QnwEF6M)Jc`=D~7l&sdP7|d__LTgK;)N1Xos*?#UplAFSNwVK5aK@ckYQ6X zBik4k{sevx<Hua~dl*0I!tX~sS3G@r@L%P@pUZ=v&V#>|2Y){g{z)F(g9nG^2ftg} zWfza{TEugWt2z&UH}jlio<B2BV;=j5*gnHseGSG(r6-R)d{?HlwignyM#D_U)7Dnq z((g~29frv{Q9Y(u^>whe?dqK8>V$_g48zWE?rq<tr>#ak+F@AG+1DIzgLrypSKN}a zF-)lR)`TG^TZyD@L3f7@ar3VD-k23j_M{Ct_u@<pnlba+n{F1_4Xd2VU8OyUw%xj^ zccv*>q?{}<$J}HkO?|H+4d0%tCZns(8A2U)>40c5-45w^S39(K>b+P^nHGLpdTShW zPs407tcFg*+-r12`;f9b67MvUJr)>gE8eN2kA|*PkI`d5Z$wXbY&Wb3W`gy}o-Q1- zVVJw595!Mk5|~`ZDW8Q$?6qi$#th1OA<><t$aZyiH^q{s<qGvX;^Eb_mm!+$YLD-2 zrEy^(VZAM$47IhHMmlZtg^j(q5e%~t9pK74Ge%zRrP*e$lb*&z+uEkb6H>ctxoEmD zW3GwmiFRjq0<7iAjksTL79dJ34<3{7bzCR0miIgH{7}MgWqcV*`E6S(;RTZYX2w^b zl<}>M--J@;c|gKt`(DN=o?9jUehK$W_ypq=r_4k55*2s+XBc<Kc}~LRIKN?>;t4pE z_9y=SV3!4PO1K>7TZ~gYT($eZ!wSVC<7ZeQ{@WZ^_UG3UzEQ$e4w~#YN%%p=-Saan z;qrL@z>0glPD;2u&tr_c=jROL?s<-JXE$y!PCOf=_<JRLrnFo88F$C|io_%DpD_u) zYF#8;d`Be*=NNa-+xv{W<NrXim*bq2>}C8j#@+F6=JyuOgB<@B376wfFz$}Cn{juX z{Spu5<f1$-@z55V;D&<|kBkpXJn~nOF^PwVXfsVnJTm@49=w|0$22aH6A{s^E?k^} zjf~THW&2teF6_53PV;;xkCnvFC0ss7hZuLy^I?f!9@l3QPf+47<sSmv>#~J$ibu9T z#P|(}%khXY(w}OmPWdPm)&9g>mhsh$S4+4Y=Vl2f9+mAi2`78er%}SmzMAbHkZ`i4 zHYzbk%*C^j?M1tYQ}kC|_Tqa%wS*J@YSuSPIB`z0uCXM3vR}ixJN_xgg@0kMG9F_o z;{2TTZV4xT5no2aDW0!cKPcg3FV6O}5>EEO^K(qX$$lg2CncQhi`f1Z2`77Tw%?L) zvOmE()v1VaiT<jM&f^oTS4%kYYpidUaN>N6bvOS5jH@h#-xk*0{0)q|`Fk1HSc>(E zvEC@*6vIK*g@3Y_?_tqT#PclM%j-+_G-fIp`*VJNPOuJvbYCYXu_!Imkugy-jf5Vs zFujIA8-6Q*Kr1GQ0W(PonQsbgMwN^(4-bemd>(NUN6Ewi9%RH$$g!)Pj|Za3&Q1f9 z;r~%lk%zVzUuScy8rPoV`$;sEiVDjcQOf&8G@rmfHrR!UuS13W(3(+M?Fd+hl5ly= zsObatE9?oQBG$>#oO4Dt?*3EU|FAG*>E@$5m;B4Q0hx;aKc+^hi2eemeVi-)YWxEn z6|tWkZGQYh*RYav{;qc{CL94Ye>9cCznH)K5zFQO82f*p`wJoZ3q6dLT>fJ>I2IWm zDEX(pqQCGTLoAp7UjE5uheI>>Df$Z_ij`dcr)XngX|X@S9zRiv{=z@~%%98u1pEJQ z>)(U@bNS!FFO<(E|4VZCKgj+!vYil(i=Em-0$|D0X~#?u>74Sjg(FUKf05^vB78GG o?(x$yyZ1gZs7vV+|DNC?7yg}A!2i*ayZ>hX{~uXl$kN^aKhNN$Z~y=R diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/crtpservice.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/crtpservice.o index ff3d3d66f7facbba26f69c7a37d1d2f45fa8a889..929cf65b3c3f0eceecc5b3ca3f73e3b6ae87a317 100644 GIT binary patch delta 417 zcmYjKze_?<6u!rVe7+yPr`Y8|go%;0gi9}4-V#JxqeDXxf<ly5AVxzt88rC#9BeCS zYEo?JKWKbHV}mr*)KHs~-KTeW2k!aK_v4(~U1{ao`N*5$tzT)Qxzsabtn)LOaL-Ru z)BAF$Ias3e7**jZb(@48)P{J(qAWXQj70{^@f4+#Laa*ZK%x&)x$-Gk;QF{%9kX(= zcUrk*rQ`D1PU+;RfsxumUE4xWYf~AP&gmL`jnfStb#C9uQz`MiF6RK+7z(!&a_2*C z7i4hzK`Lpn8+M;iFgU%Srt>vFbRjC{jO6bU7sT#V$E~qTSqzPD`oL?#QTDZ2q=#|B zp+yu-SILNUP&qVAhcf7!E*0@BdL9MKC5D>lRrD=a@nf@W3uDWP7u6a2W7tk^(jjWe F)qk&$PnG}x delta 541 zcmeBBnV~vCgDHZ4qE?kof|EmK0|SHU17_h>3=9lYUjP3u4x$-q943S4UqHUR0`pZ6 zp147jv1{TnbH=WX|B5&mJ0=%$mJ2cgRe^vJ5Hm8cFepvl$S=H^hl_)8@)Ir*#v_v- za*0cx2TBS7r6+(?0znLfVz>{I<@^Zbfn+~S_T)AfNKMYjcS+4jtYpY6_RPyHnLL5J zgU{C}grO`Xu{awnGg+L+a<V_qM8<;28+pVHE1;%HGcqtpK-nOw0m=r6OG4QoYR=?9 z9`VT?ygZX-czGn(KxKr1s(6u9ZJ6xHD=xVONtPW+cE{vGpzHyth$v7mvh0z`3wgyI zuRvu%_Ddt_{QzZyY-9nlm7x4DP+ANoKKUoFJEOv6N51Ebe<o}4n{#g9fhc(}Ig{U< z(Pr{OetS*_plT3Mp8OIh<}g`Nz@D*Uaw3rQn7j~3PMG`<OezZ6bAI4}sNFF+Q_!4i U1viAp$T)eGpc&(b$qxn90me3HZ~y=R diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/eeprom.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/eeprom.o index a98d05b327c5324d0b44f47b21155250994261e3..8f3604e85df424f2aee8f46e2a43fc89f4d7edbe 100644 GIT binary patch delta 261 zcmdlX_d{la22%z1My*+lY$sS5LW(&ipJJTGD=))Pl*q^sQq9g#_;7L~lR76e1A~Yq zkhfs+UM6utkUYcx{~^T;3?@IBMYK*&e#@lHA+NxE6@)hnFn?fV+_0IEbvq-Y$K;)C z=3L^83=BdHj0_K$Hfym<GENTSklkFs(ZM8Hz{CIs(m(}r5GI(sF}aXCoN>eClicT- zUNB9b#bd@LzyXop!8G|6j~S!JWI<kgAQ=cICj!Zg$rpL;nNDy`7UHv;e1Vr^as;0R e=L?|A!C>-CK6B0&Y!Ht6<ePlvi~^Gd`PBhnQa>gD delta 454 zcmew%vqNrz29pKPMy*+lY#D3}A)7fTpJJS*_>h@F>i|PTki85;(LqLr5C#T@DGW6Z zlR<PfJ42!4<Xk3oQ8oq!5o8%lpp3)hxlH1cApHtZ{R#j6hZHj~nEYfG(K<N!D3kK$ z4@@5z882*p$g-W0v0(B{Hgi^fMg|6f$%V|qtWq!*ml}{I!~i6iH{W8DWYqRG3SlS< zNi5EGNzF;DWXLp1PDw2bFUl-QWk^jeD9X<TvjY;-QyDh%ada`&8!!PK2L#eUGvpvl zFlm7#E{`OhgCvfuz641eS^WegaRnrEen7-0Z|4eRyfB%Q`#ci|^W<CHW?Tgv5LFV) zlcjjf7(FHj^4J5(iD2>~kNxBcyd0AycrBPZxF-kk+A*$}JdxL)lY<4K%V6?NUUN<h Rb_maGvLv55(D*<;bpR#zSjGSV diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/ledseq.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/ledseq.o index 6c169f3880b341a454583ef91a649102b60010e9..9b6e7153d1ee3e7e753d6ade78dbeedbea81ab2a 100644 GIT binary patch delta 1225 zcmZ{kL1+^}6hL>HZMA6{ce6>Rt0HLy8x=z=+El2-SR~CsXfX$SYit9Ck~G$eIe2J5 zyx2qVD=6rpw}O|36pWrC)`Q@oIS2+SSm{+r!9x!z_$T{EmVk4Z|MTAb&);FlN~m<9 z6znP)<#W$iWrqbAn}NfwTWlVt9dDTlhmJTKuG~<cI@oxne&iivTd;eSCmM>Pcoe48 z7$&#|tf1^+6#OS~7x8`KP2yw3TkUQtQc)G|vaqyn;(6kasVYERaabTs{4%7RJaJui zBRfv^rtC(%Kzx>XllUa@hw#zK%_nGerRU!l$}fEZ`)JqO)}hE=(!PhmK5l*{TcVB{ z#cwc;_7`>Tto;o|v@No-R(9@zGFmU*h?r`fI!b#QcF~TKt##NK=&mnk3dz*{g?M^7 znVDOdSbUIMRtm{XHoX*2=h91=xrxPWHkF&NsQm?2S#eJ>_6X|7xcM9h66*xU<5t?< zt8h`{W{s?YQMK7ENNJpHiybC4?JONr_9*ewdCC7!Vn9*jF==H(l^%ka;gp0J#dU}! z_(>~m?@1Wcxw&ey@}h*^XxmM)VsiOhg{?wS=Wthd!E4RMzC&5(36-9RIO`RMXlcZ+ zARm$t<89(%E^gzipnJHv@gKVhF|<{(@(!>?dwqp_9zL>7)`!?WwS2^#6Sf@i!862y z@WaFVgSJt^Q1@^cFkI$&8=a+`VfzqVHMkkFS@|Y~4MP^~h|Sh)wU^+H@rjK=${Xpu z=C(ut*1Qo`fQC2Po$p45{{aSseL<Fo8DEsu;1%w((7^pAnEt5qpvS5_P~nb$w71!3 P{hWd|e*~L1{KJ0%<dc`j delta 1330 zcmZ{kO=uHA6vyXf6Pq?^yV-0yiB%f3(ip7m`qe5z{6K4kLW4bc=%K~-kV7jL!GMAh zJn3cI=b=Icd-J20644$MT09jI(&C{#6mk*;4^|Ys2)^mQktN{5?9BfD@Bija_HEqG z(qT6f5cXnr2GUg{m=!`i3fwt^K~Y*aXxyVwHRKD$%WokKkjJgS6&OaxcnLAwGWwvc zd?5JHfZ_6D-5Y?{xDuA|LEQ(o$Yu!;RiFi3NpBKgXjWVVJP>96i@C|Xm$?cx@kS_q zH%u$#9IT13n7hpHv$LIf+VDU(^OMA5Vwcd*y0VKpKgXZu_`Ju@373T;3uA0BgC4lV z{5EgEkN=MT0OuQI>hX@ssVGEeTfj9^-?3Nc(#5SJL}Y4{)e%mu)z9ceWdAm2ep;id zpIRN*t>Fzj+z?AOJc-k^R|l(=8ub*eL?m3m&B$tU;K-0D4izTGr~1Yx$EOO{&R?IH z7@Zu$`Dnbn8odSTnB`nk9-xHN&9Z-%N>o=X&AYwj&VA0uTYdbMkNe{{aHUy774xRV zUela0!|)xqn`KJ3Rh*3KwXk0V@oY?v+T0>q)jOq`x3Ej|cIK+wHVtV$=Hq*P{3b4% zGPU4S^&3(_6{TV(7H!l`ujmHGVlwrUJ-RYo_it4<w4-B5r<<EbHSm6A<*UeCRVg*3 zc>(7sbLBtkCtM?SgH?TUz3(>!OJcVb&L#-?>($+^Dz$yP?Fr&#Yah;8Q7qD+xlw;% zK%rTDV#(AYpJ9a8O6|grq;~mK-K<J=@DHg+ed@B$dmKCC@8K$L$9w8aO`b4_j@<*Z zSg>;;H$;s7lj68+XTZg;c8)sdU?K+<EYN)kpC@t+$vV$zhVVz?M16*jJcLe54?M#{ GOUGZ85u0lO diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/log.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/log.o index fca09cc6567395d6072e28cfdde18013ebf5317e..8cde0c14f9b44d975f7371c64edc50d9d29d4d89 100644 GIT binary patch literal 23144 zcmeHPeQ;D&mOrn%fj|&DAwY~N@)D5^DlvRXqKtW+M1d*PkhD5})TBGz9nzcc?v9f{ zlm;2gGR|&VGNm(di-627Vci<m!jib_PGDV^8k{N%9Ot9l-OkGHx+`m`=twKr`#bO5 z3pX$H)Ku;Mwbifa+;@NX+;h+Q-E+SluY2cRTkdvf8p%te*XT-4qC{;EUb#2STZ86P zE?wI3#`q;CB{YgRo^R5|3y6kyJ19{*sU_;@p<_FV+M&=}>Y}_FgL*ybwAV0YJ>!>l z{QaRxXY+gd;NyG0SV*aLgT`K>MW=S5zV4<WT5F^xiH?@&&R<SB=`fLzs>z|$SUUac z*k_NQ*$X+AkLJ^mZ?=&d)99#+;?FrLe%gVLA0L=HA~BX>e80eV&W0}N8G)Wf&;uXx zU;TLS48gu#f4uJ4`6kc!7YmJ)w3F>{v43Rw%lSGoCfHZ@6SmIqll|KRdG=A8EIk!> zYeScI{A`?UV&10N>M~MnFSmbb$8nPz<`>v7%fkO^=6E6UlNzm!!EWa5hmPVz++j?V zxM)=zHvB4`exCC`LOOCnOYCzj`bY!s?28X|z(Kx7#R<0G;hJ--gtU*2qnsSOPowXL zOJOfQL)<Ptrd)~3aY4#4FOri>J6@Ol|J)akIL3d6e)=-t9AAXGuc0lr_k1lS3ecBH z@DF|Pk4APG&onv)-Az+vG;kcY`c_ka%VMhb&!cMZEIPWY%&1-h9bZC6s@*ky!AUoz zqFN&TAWf9cr~LFIG*RQGUOkt*CufltanU=u1nGS0Jq|2hWK8UuXQaSM?^Hf{lg`4M z%3Q{{K{f9sp@a47^NaHxliJqioa-anZ1f%U))Z5392_PeG~S?Jmwq?-2)$7<srBw( zKwh82s4i)v-W7S|O|{pLzY5!A{~>lxk176@6jNl^Jn{~s4+#F6vGhpo_?Lk?aQBwk zw>5>Z`Kz>-+uT2Ay3NPk(`{yZwPX9gD{Y>7a^6a|+lTtxkEMgICbsW{Gk*H3pZlvk zbo(jpui6shxkHel97;?zX$kZ{_v;ADKJ292?GCCQaTuwQRNCa6`DJcRF2HZ;7wKtS zG7l=3R7?w*&zIBbB{ksMW0TkB&XCV%d5qyDH3jIa^V9Wva%}P&Ed3*pA443m?PFi0 z*PUoFCiL$QH72(ni)cuvwvI)NLAt&c^UR4BnxLHcLipdl>GQN#v*Or{Ym6Z?2494} z<Rj=~=<|aM+CZjVH9gc@{%P8)7aPyjn)8HX$j%$M%ma_ruRzCc$RwTDVQ!+4WV12B zzJ-Ak>T{XNdtf^6<hJS`fLxhcKkBLG`VRr;wlC}bo5=yjn`XB6#&%%SVx41GiFN5$ z{S2Lksq;?Y(``6z+E4{to$qomCtYp6%b7)aC7vtux}5K5LA<ess5d81AH4>B3VzJF zWL~8)F$?!U!Mrjb>9ZOo78Dz)T(_2(i#DzScC9ns=vrr_4$h;aNvG>D##p06M<1c@ zYK!a795~rh6(C2h59`44$9L|Hgj=h&X|son1(ZK_(pTjqXYNjn)3*_OSQB`@Ys9== zP>a}TCP(iW#+sAkAWn$@bbRVEsv8D(?5)N6<95s+s`<v*yWc@x;|W*OTNpPbMKqD` z&cCS@ZPb3a<IIY=ls9`GrSi+DdSAHg!daJP=N{;M6Z+glsTJU*M$_6)r7-r;KJ(J7 zQSX2MF75rmx!~{|V2rntQT-HEt*>#+Y5xz{mqh;&(tr=`(!6$_w++Z0Mt^W$Zp$%J zPcCu{y;XSk8McK6e>%DiYvN?sSJhfb6Gm6@8lP_275o~utfSOFp>ABWY+$~a&rF>C z0QMzO&i4La_5VuD8M6O*?c=q~9s?W~(_#QI@o{=zqZ_ec+JSfo=Kf*v@Ydvtp(jL4 zOkO)ZCZ5d@6FOp4jfv0PM*mh36RQvt&5i}_Q;3PlorsC~l&C>WEOjrP78A=66L*T3 z2x1LmyE%SkT;wTnF(l$buJarlzra4}1Lw7uV}t9<_-GdK!F#Ez#fQ{$^%yx~#z<1c z$Yl4G7;zy+@(?4x6)__9aE$yFFph=)<k%B2!E@=Q9j}d#A<z9N_ag<sqgW4lFU9+S z#mMs>fcFB0oZjIu*YVVO?UjN1fB4zg(OKg=99m*(4aq&haPkiGemGe}sVV36hq(>J z%?Q@k=X_#q_07RN;GziTRWGmYekXZ-xmcI6R>h0Ri}}b~g1x}lbx5%nC`EbTTBCXl zcJVy0eIaDQD`C&3nfp_%J-(E@=G-9mrw>EUk53XdY+r~yiIXt*(1={?*%n^!8G8@h z7)xj^+p_;w^7@@dwGZu;=Frws%qOLB&zYZolYYLanDRe@YzfwU9s3dN4|+Z5%Ng>6 zzZvB^W!N`xoqy&!yiVRi-XhpEcq#q-Z-BAS=@M;#eNDpWP4IJa9<5ETVcW1yI<0js zaKadvqdn7jwj|!T9QAj@ZvS&wkMgy|HYW|V=2G=ea<vC4_Y?)LwfvmA^r!jkyMG}K zu#bZC{DW)@@2|d0dvAcwTIlkjzJE9LEzlAH=wtcIZ7kNz_4=~Dz0|Mj!`{eT=lrOf zbS^R1&~2-Yi8R)Yd*Dy&QX>VQPrr}81K*g#5sM|BfuHM?$iaNh^Q#AQq7QuT!JPSU zfD-#?PP-4hPPT2YD&zU|o0{7$Itva{dd_Vu^JsYc1t~Z6P1;*V&op|Vm;G&l{eJkP z+PDoiN}D=`O~tV3w<4Yhb;IcID>gaWcf+Q!0&ASU2%Ab^QyexOZyT(thYeG(=_}Zz z!6w9V-oxR+3sR14;`l6uU2M}%=2!44`=OTmA8oz_8-m!!PdS~3%Ww`UMNF5FqkR(V zTMfBB@?-5_-dJA?$^$5G#u>r4X!<$j$5<P9f51AQy=cXqA@XmE{D!Nv$$DkG&3w*t zk#`^VoZK$A$8F0tb@*@k1%LS*=(}ji$Z`+r+<-IELHOjyIjQvA;F$o%(o>`j#oJ1c z{mWWPy@m79@&Y;<z}O04Z22)xevR?K<D>xg-R_7t<|F;Fo7Q6eP8iVVm@GS`yB$M3 zc8bOM>R)k2*)u<Wn#Xe~K1pY>8GBCDo&D{&8P{jqX<`a7$#LDf(2Co$?Z$)y>k-TQ z5u1C^&wB<BjFz?qt9ZZcUt+~h3(BU@#?*RB)l$)rA=;f<&tp={r9#TXzB#|7A3R`g zIf?U%w87!RJ{|gfMb_AnIJb8ZI&Xl!?a-HW7MV7)FFr@{&=lv3wL~rIbNq7bsB!%2 zH|ZrV*sj6mFvhuK9{W*rxODK~Xbb#1-sZP_z<kH`ru$Gl(}#lTK0J-{leEe5q3Ezr zjDLx<4`*TTS@3cL6;JcyEVyA`*bkq>HAID4;uq+TKO`oeaw;()=Fih2F8&05b1b;9 zALTjG<61V#{yhymd54i|SqV-sUnXnJ`O@U>&(JQHomf7z>>oM4FkW^eCcg(AMY!)n z%CXHKc^>97YZ2DHhY-WnZd%9d<_B2&c)bi@{cFP7S%BEX_(}14xd`#8<DS>cCAe={ z%4?zH)Xr9%WiHn3r9tOt3FbwdlP5YczWXtUKQ>QG@H%=ubnk$^>o6y7Ky3JC(fU_s zQ{H~)|64p0kuhZPi`ZIf#g-5Kfht2J;!{JP@|u-&E<QZcV#Sdk^RW*$)X<{#A7K8Q zauy!mZH}46W_)p<>TR*AQs_a<R@23r^}3ArC$Rou|6Gb^2{mo>=_ah%vP~X~cuuiI z+Qxdm#2KIUun+H`?Ca=V<II!qfMstGwh-*|&8E~oaM6kV7}vwRzLm!%uXQ^1&3ov; zXc<jbhj^|<OtsL3^)DgrtHEmt=0$=G@2dw0Pne+JIY|TjOa*5;>=BB2t;yH$Tm*BP z`CMe**Xid&DC0gv><s@oWZ+ZcC&p5am&7vYHTMRqt^Eq0^>tuhi1R+$sOIMd^4!ll zTCOu?G1jed`a1mO_~9~~bE@V3Tke;EV{1jj><{nJ3_ic0^RWKpOIfbZHZm8bTn?WJ z^ON4@tHQ%NQ_hL<0Bo+oUNne3H_O0Jlh13=zX9yK=b%1wIvcWYLAK3DiGQ0vHo8au zi&0<&J89NO2IlhsaO@q-dmn5z(lxi~Skt(?6@ADYFNba)?hT}D=M4K?2Sy2J8tDU< zGq*a<ag1Hs@ptBVVG3t~8eMNcpG&EQ>=))6_&=<{RtJ3bKe2z*z#QhmdcnT(eh_iu zEk}&-9tmT@+z%ed`ASE7=X3eF-ibrtdctg*pA$jWR%Z1B_G~_0m$7G?npq#u5UQ4% zI(VNpqkM9J%g|4avQ5rwu$}EMg|A2x2X<Mpa|&@_v%#!C9h<c5GUuDC^D_ot%r-<U z_?{RWEkhjW7>ge9oGS@ilg@=Vq5Tn}vZbnhG@YY2u4?o5Et~&c#IA^6#3a#!p2mAO z-@Ea4ean3t^&WqqJrs-T!AN(H9t_1ofmkT0m*3dYce$veI~rRtkEo}kyNBz`tF9v) z>Wb-o(NI+H?g;7~-P^W>ySC|`hRvlAr;3VOJG+B@9iiy0(MaG{6jva;p{F7m-X797 zd`quu^fol#<M~c=y~pcmZrc3tU0e>cI3ZMcz#rKh+#G$t-w_U$Kjx2wgDX&=Ib8VX z!kEimSq8EUWEsdZkYymtK$d|l16c;L3}hL|GLU5;%RrWaECX2vvJ7My$TE;+Aj?3O zfh+@A2C@uf8OSn_WgyEymVqn-Sq8EU{C{I$V_n_tdilnC@7KNE-5r58f4EC;?T+ZN zwvg^w*%Rq*4R_!!5@-wa`%Zn4kX~J}dgbcMRn--%R_o>dNasr2RjydUc*QE6OIB5` zUibTn!aH4f&HB^y)uf!nr86&lA8IBD#0gFIYmN!b)Wh#uITZcpM8)d_{)x!Tm$&fV zpDFJXs>Ve5tw=SRLvHgeF=X7L0Ev@kUCD^M+st$(UJab>Ns6M2q8)xI(8MiA$Sq#r z>J|7Wb4`U*D9SnK#LI;C%W8KfJ^(>Ykr(R7lAp=v9#j4bE}7*oVQSzX-(xT@neG+1 zq(!%iiC<b~`AU(O8ebB4mB6K*JK;CW8v@rwiWeSD+$Zw#{kB&G9u&CL|GL221U@WM zPMqjR`(^Pk6F&(-?)S@=xaBX=n7GJG{r@HKVS&f-WkGp4FS8~Q*aBiDXID_dYvhEN zMe#>C`o0(n%QDDUWx&6k0e>_D-jM-+ECc>{1{~jyysBRZGT?um0mqjyuBzuBGT^_; zfPb6;cYxok@jo{MUYG&D0XX-UJJ0IH4aoC#a|Zd_GT=rA{QeAhZwCBH;A~F=UJ&O? zhT)LFeFE3bQlcMa(DRo<J}%_tIK_A5P5r|*JtqWyMBs6u|Ca)<6!T}Xz&{XpgTQ59 zd@OLElt=&ZbwS{9d`XY5r>%rs7#}A8i!DIT1N@>a-mG2L&o}j<4!p!$+tD3p=WJ7~ zyXSJIF%%8O7`?A2O3Q+L=jrJQbp=g{ia>W)G=|l&r=rqU^uTI+q1PX6r`SMGXiKPT zTda-3(al|9Q}-5bxu?BiUDcX3tR@NxGd2Izb@z3dV$r%tfDsn2?Q3lfML1^~5~c2F z(?GNtd2WV3LSh=;6vL~_qM+X!?hHjXhPpzLaG<Wcv(w*Yy4Tp(WqIGfwJ+2cY6^Aw zd)m4qA+NtZME$IJV<_eg2ih&WEGeO;3B*t!66@I<t?TaUGGB}~^A?Srq0T_hfC;c< zgZUmcHE-N<U#(|L^L=;U-E^0?+3Ts@a#u4kv)vt`hQ1g!BM}PqM8aLMR*K?n>5kCq zHh)K})etCTn@n3pQ-M(Uv5=+Q@`NqA(x8P!W04N9{Jri-dnnQrXbbUM*W`~zLy_3s z{%{9VYxWOw+8mAfBQX-Uc%?fK39MON=kEygb@&lFR%i5I=Bh3d0(?(jEYuImW8r{B zoCOPnyDAhlJJz&_yCX<FkBM#p#ps^R^=t<SH{a?O_g=)1xZN1(?(6Y%1@HBDO2`uo zMncgj3!qXHUK<y(o2@8<vb#IF{bs|szaO+-nd=r}JjpT0BSs7}T4ck$Vtm>0!3_AA zz^{j%GI7tzu?+Z|0=Mh`MBsKiKhGe~>mpxvJq-f4+Y=Nx>%Tl#pgymEd@Z)&F-2bG zZBXF$c8_Gh-?8bD`^k50@)CdFCa;T*O4{Tl&g&CjcE5@R&UUK)RtlW?S!Pu=|E^W= z8x{OfMgO%5?o;%u_(cU*+jWcm47baBZg~|b_#a6S=`sZ`SMZ|>&R>6!SC43n_1`2x zqz47g{P5X8UWXL?W(gvFS>Vi@Dt|=a)xd92<ncp3=Ed!<RPad!uTb!F3a;9Z?}J~~ zqvE$@z&B;U@%^Ez>gmsbAI*TjodK8U82dOqE9C9tqCgx??0C7r?QwgHA}^>i{aLHX ztMOK)$gB7UMV`m69AAbaui_0hc{#quZ1NIMiv9i!9t3Xpw?J&9?0C7rXYioNt2|UG z^3(iP<W<~I<W+y`6?ql++T^9bM{V*Fm*-TrpU2B4v$rtkh{0p`D@Vck))4aZ1<w4a z{<;-hl`j;yY*(Huixr&xlGic?SI2w3z<K=MDut15QsnuzO_Vj*@VLNzik?b=anhmS z%M|>O!0qwyp(4LZk-w<m%N2Yi*UGRS7LokFAaMJ9^`gM-^VK^FuFgM61y}8HivtGh zQRVdvc%_1?dbTLIswXIL>6h%^cNKY6&xH)~ZTO)czSvGxeo)|c{y)ipH!QI9*yUfy zfFBV!w|k>i)%<%>!OIl<Lj_lPaErmrdR8m)<r(lT8SqCHT-6^`a8>_c27E-pRXr~% zxXSap3a;uumjQQ+1EJktUBT6M%N1PJU!MUF3f$h02Q%O=3!KN%4GRB975!@z{7pp< zk4HIgylundqRu;tp0$deq)lGx`Ot<-J?Ap$DbBN$+UH?i;P!oQxgvkFVo#O8nKyNQ zHU!T6SkKg~N?R0sy`pE2qF?3bX+^(^9}>7d9*!xv8V@HGT#bkK6<p3GY}Q2uSM?O; zTSnX4t<Qk_1a9Z2O_Aqk!Sb5SAb(Qe++XVY^|m6f;vZ(f&nbGC&oR;PCkoD6b-8|D zQ1qzsB%bTAU#h%Y;LOkMLN_PN1a6P3wE~yxwIS+kQ1o-V60cYEtK*_U(WAzpSK#(` z+Y~+D5^ZwQq3BWLykFq<@jfW<BKW&T(KD>*VS8k3y&&+VkXP{|HhHP)sKD*<^S&al z@{?5LRlHK17v*@D_EZVnZcl?EFQ#PEB(K2P9u*%{<W;}+WYAwFp4-WOm-E;L8-7R- zVF;YtWxu3+y$zT0TLjK=xK@&h^hHI#YUe?L+j)3X(Nm}BIj87R?fJxpOM5;SxZVB> zHeAY+cz$WO-z{*CH`N}hhz@kd{4Gdh5i4zzcaczszXDIDVpI|I$NW^$5{*(tq?<D= zzN(^1W~m|&=roH1ctD6>E>K+lU)}1c4U?7sd9u_QRzd~BFOi+`EFQlRV~!UoFXgK4 zvhLmy^YvV0xt$y#P$*K~8#68*69^PPAYp4)7O<>(-GU73wAcTRsDD8f7P2a|3K`b9 zS_N@0>;KG#OZ%lA2Fm%K=UVkD#4p?N#eS=otS_-mxZ(PC`^!ar_cAGIrS|#_qJHIc zF{--50v@s9(rz`i+s;*95cP+}d78&k89uUo*?;Vx-F84!Udw+m7ugDByH+XT$DXcU QKj%S9;vp$0QhWXX0Zb3A_W%F@ literal 23976 zcmeHP4RBP~bv|!*L9&EFh+l(>o@7jcf-Gb(l1-ww5;l-v1JXLNO(xpaYK0X2t#((g zWMpfFm4;eQ%^G>)j@+>zNsE|tN<DUhlDJuj>o6sqxHfg&B<-w<+mMoEaIj-G7;nGx z-o4`LiI+6f&UB`;cUax`zI*Pu-#Pc(zsK7hxM%0RE=?nuH2MZzzmq7@v4^i;8|I}! zb10v#?SEzbnwt_D#p^EDYvT)v4jph&q9&;&YU!bq14M05=qvHi{Az=`y_t;9FlD{t z*Y<z+Skm3_mfru^;rAC%dQ-n~m}t@2LDbg^XqYw{=_Juh#k%_+C*5?M$VgY`QhF?t zd3o%YkG**qax5P$q+$PTBR!_kOCE|p<EHo<E_?#`fa-|EScdT<0w0(SUC=WEJ&T|R zHWa@6i~ctW{02X_>Ez{l@A&%*jI`v*JUnb4S@!aMEg2JRE87XKGwfvhh9J*2YRQtb z@d9o5+Wzm1Gbi@jG_D>a&3w82Yx_@`zG43YJH)cEzlwdl0QX6aHpal4{r0S@C=quV z6U83d5C?~U%4EL8_kW6f<g}J}!L{h32EVf{e$;^v3N<Q9Fn^aP=VUQy7f+#_TnFAj z-ybRgUwnqSU3^TrVvp;Jlw-e0pRg?!H-a1K5cd;vH_%t8yYSlnZ_4<1=KZ~{@n50* zgP?nS5oEssE^N=`8cHlgU#HMNr~~_HWYBoB&edN~KUqqBr(lb}f_fVlQ&k|3s(iEP zrNL68Y6*0F03GQz&-fKLtxZR@MCQ{pQ8I@LGka;Gx`4X%eDa-{MLxt$cXA2xIn;d$ zSbUi=F_>qh;j`|^Lh_~DOV^fqjB$gi-%3FT>(}QL6}pnzo`&4z5p6d57J93Ts5=fH zr#@}GLT{IRHno>tDNbtLN9K~x?=q^2Tc~@@eDbB+wvN9HZnA$7TW^dh_7xXVWH66> z2hm3ad(BweTQmMauok|3&FuT?rQrPQjE~zqk~5w2se<X8nXh*8$Y&+z$tUvGGjBiY zb3d2#d+M3rX?OgMU;ka8(o1)p<^HTGHl8^K8Oo)^WWAO^d~m;yu<XNb%74^FRU<AV zJ(A9tK4<^3Z%tpoza{TyrumZnp!$-EXaW24YnjZFYWUh~lh<yVAz#Sy7~@N-7ox8& zPuK6wwaIU>^p8M(3~|KV$KKCuI^AeY=${|1OYJ!s(U4E>8H*VGw7drM(CJ2+pxpQZ z*x$DOy^K$@;@pgTvf_5+dFV^+MIS?70KT9tWb&#GQ}^n3Gd{h@c&5gjM_j{pzrmOD z;m4{Mq2mB#Qtn$YchN|y!I)s%T7eVlbD8P);B>!JfmQz~<Vw~0QEwI3e+W3YJ*D?s z$v(#GXSVmsqrj%cI>)XO>(Z{RGjtlJ&W{71&f%2Fp%S<{ALe4ty3u@?JB#KQd#}&? zaz3QF@w#fF?%etM=*{R;_{W@U^2&{gS-Acx=AAjnpVBBXx5!B67ifu_(8kTc=DFi_ zo=ryjD|z%%%I!IhF;?f&(MRaJnxd_59zD}o86;P}AM3=b#|92ZTAM5PX|sooxl}lI z#$V|scm4pz>Gu(PSTlG&ti!y%um-WwK(6jFj5RmML7Wmn=y=y-RPFBHf4BzgQ-N#F zaP>#-?jtVp8IODFU&FX5UPcpz1%+#y(MHXM{co<hiRRDFqjX^@RlU$!dgUFD#d8Qc zUxmH`qVyX0rCQV4&ZaT;&_4U6L8I=U|0?4<@1A=+2N>hcWK{hTRc@|!<+S|-{8H#Y zLLT&^UCL|YdEJ2Aar6iG<-S}a{lp^I@M}x&eUrIR|6h&n!<w0F^;b48r3s_6=nlVb z@oKsXE}JO*FQ^;WEDr21_NSB2z6gFPlr!J|t^Qw+IYaipTu<yVz;Q7x1`rd!$h=Tj zfLJhjARe0X|9kQ9T5`?s<02-K^QOndQw}kqBSzJj_+^37yGO*t2E;^zYi`>lVj?+! zn3zL}YQ)5ff)&$ZVijWI<02-Su!b>jj$auU^Od+57I7i>0UR5DkA2j6_q?gt;QBH? z8bo~XUh78jA@$riMoyS9k`ghJ?7AK!9>mCe#K;dtj7U8kBYz2uW8tS9dm<*#_B<II z%<p%-SL<^9-*(S)_qF{mkB^~!-iOHj(L&%+tiQas<9!G3H+bK{dxoX>@Sfq<m$etu z-*P1$ec;(&UX9Kg?{{g5$va5yK@O!pX<i>n?GpLjl%8}K9p|<XuOnE~pYe+|J)VR4 z$3qbVal(6wBW|qM`PdI&jZ7{h-*)Ulim?Yt-GUr@kN}r2FshDPdxW~7d8nU@4RvpE zJ=^US`^p!vM)^y~7sQw!5c_8@+Hb@s1ulaNsOo^5F!#|2`o!G#GAG_|Fm?`oV=SSK zCZ|p08+030akN#EOM6N%pOwVDZ$AA|=1W=;6<&mFG4>of_Cwg8bbAp?Gvxb!ILdWg z*tc+<f8{#7PFIlcfos6P>z{$K?U@Fx&$Jn~Z->3fJldGLgSk;6g*^rH3!XOma<nJw z-YJgP-G;gcz&r2^*26+A@dY>aeLkP62FTMEEFW6-#5~K+$!kv+3fucwhwyzNub1rG zQy*k}w?bzPbj49WZ~*$|YKbSHkL9P@Sge`*g(-c9saMtaC(y?_0;nt3+E9ft@g1yN z_rac~6-Ih7%9o4t508lp4c@*#)+v#T^`sc{yBBk^vDoUrw;BoOgjsEV_%+`0NM$L{ z=O0zydDXq}IAwC~<UYQ;^^q%5Zt|myuausw<NjuQ(a(K@ut((>0!PWI!^X*ldW6qG z^!Ig6uC_*SiZ8Y132v(xoZ{Tq;8Y6^lY)~5PKfC#PAtcqI6h0ji#fdjK7+!qvL6g^ z`U2YI*sjGnBjt7-*AUNyb5b?sw2fiki}TXO0M;({8SC3C&rvzFfyW5@LdN?b)+XMc zaNIV1XvH13!S~OL`z<$Ull7|Yrm%;X?Q(nEwt03#n>y@gdD*W2!;DYm<ONqA3txv# ztvJiAId$vVH9yB$@v(T_S=UX&KN+Bj?|p8~$)9ef^u=0ApU;`UhWqLKF!nRp>)>3p zwiL0Fy4y&<gV+!D-!_W!M984TcU|t`zje(r_uUt3jr30jjESFa##wC^r3Wzg#+P7S zd)k=LFlJNkoV9Y?9^vtZF?j8x%#spUyzVM;eI9LOjsb8iN#1()twL@1M`Dh0VZ0B` ziN686-xy>r?&apb^es{TZ#bKk0GBc;_hPf0$MieU?fC@!h4S-lG%<-iEsv?81=g53 z-)2m>uokn<0LDcSF&6AUI$F{atmL!8;1Vlt8&L*d9G`@rYH0DWA<n#$u$M^7r=>I> zXNJP!UYxTquU)vA_p269mj`DQT>F<<<5uF_-c{(l6Z+T|$(!x*yOs}6vK>WQq6YQ3 zPdIMXF*E|(+~BT(^Fhopt~|?*lKwA`9)Nv=Edk30%(Yzax7x69x(&z7GmFgzG57pV zHZ0W=KR}$j5Kl+Y$0@{7z*EX`#A{LAe%SGU6{9%sOpDPTa7lgANH?yBUwOXYWzP4e z|DS>lTy}cZ%(AbejK}+rFqXDKhlcBWkn`B&k9?lM>-RFO;}2m>Ru#}D-Upn=dd};A z5bJq8=H!Kl)l%%at@S@%r{mh%17Q7J!E3tf>_9Wlf*;l%rhfNmG3IqVXPD@~{=XM% z&?9+Tg7*c>p?g2{-GVuN3*r^ya`VfxY5o!D|2CdE$#~*;<Nbkug%zKE#3iZ>lZbH* zalvDk<8!3Zip2od6F)dq)1tO7V*Z|VFFk$$dSwiAZ0jwt$`a^7+*i?u)thxWW**1- zjq^tdp4C*h(7W3aXR^&A$ly8963LDAe1JKK^{@@EqwH$*o^ke*|ER^c30w&L{Ie<j z0({Yd{VdlT^3Wb0+q_omeo73{(a};$R)u)2fX$6`W%HLYcB*(TC(lKK44+H-2v6{! z-<_mBerAOj!C9+_pA{Brc<$7IHQ*HFwq4D9DTFfaL&Wl-KZgu#N_^E=!SRw<3B5dL zxhkxE7e6b}fxR!Dm!OR*e%>OVo3M_?TTEGVzTolkP1wuv!(})pR>^%O*2hA5&E?F2 zZ7t#RA8aDbVS0<d5)V5~IXB9K;8cyhdK1nhECV}Cf8C7!3*uaogZk{V*^qq=vMqi} z{QI1-(INdWMu9EF9^j&Z^(F`$dmHoG4^Bp=`c55dE|)i>kJyK+pxcjY13B}Y!OwGa zlyK&gHgGxnPRBWyv1|MP#(e%ZiL+9*uD4yzr}P503u__!LIYP9Yz;hqWYoYs=Ot~J zZRLF{;=s2WF~EB`#Jst0J%#h9j`l9+^K;SD$KcBevu%Ek23cE~<!9_E{k(6$o^o<# zeLQ2STw&_qedLVtWFMFDK1R05_Zqk}{}R}WJaKf;ijA}AXB!8z{&Xy9@iOO=8~bMr zwwP^*SnxkSHd=}}&@tA$;yGXnTvP4^YtjA)QRxbmA5HhsD>vl)d5iOZh}abIiK7eA zr@eLe@3?>4UHZ;l+w^cC*cOUK^`=NySZ@l&Lcv(5Nnd?id(Tu+dsj5JCXXoG-WBHh zGS#-XhB{+<Pc#(OyV{%d_O5;VT08gY-rYM&AWmgvw|8_k^|Xhgw?`wv+fiJG@P?kU zXzQaPeapx6+B)CvhWoq^Hf;6!ybbj`9=?amA?R!E2u1js6KI+_@J|IIJDPSxKNV<i zZCd?EAkx~zJ0Z>G!9Ne45oc4@16dDbJ&^T4)&p4&WId4eK-L3U4`e-%^+47GSr24A zko7>;16dDbJ&^T4)&p4&WId4eK-L3U4`e-%^+47GSr24Ako7>;16dFJfAhe$+S<GH z)!XiWK=*ZZwFg@Qt(|&vS45AsgmmxvaHOlbwH;THU`s2%|I`x+=~ZPF>nqAPRF!S0 z&{qc{9qVybzGe;MWgB!Z*-&1w={GwH?|9)A_jfZll5!K5&P@3J*h~<J8=CAX#{_2T z;difGivFL8ig?G=#4m|^`7#&Y12l2JP&FpXZ%3|C4i%Vhjp3$16d-fctm`-8>P|DC ziB|zP`QQabP9KVP_$5IT#}^tn6^IwOx^c~ToDD&`U>Ry&yYX_NJz4F}#PN<Ov|Pt; z5*01^nf@Fy<*(z?v;6YB2LB71Q~6<mOSkB_=fp2fvwXRE$1z}~FAKa<+)I5YU^mMf z0@p>37a&dCFYe|0Z7&MEN#IidHwE4z@IxZ!%#D7uC(92r@iP$QexFL>lE3t0;^JQF z|4)G*5_lY6u9V3=<t>ST3mhwbb{!>J3cL_4p!3b7i^5e7@|6zw{X&l}^!!*1sfQip zTOIJn9Pp<d@FNcRUpwI6a==eJ;Q!!&ryTGL4)}Y(+0O-He91WEFHbS9+whMBUT(wr zg-ez<Y<Ql)cMDv`=kE#JZ^LgFc-V&50KZY3_#E&y2YkQ*f5HKO(gA-KINKX8v;uPr z?m7LLgZwcE{6z=+dk*+{;N0#BF%Qe(by46+fy;ix?-rQyuM1o^Sz=gW9I&2C0*?!P zk-)?FA|t0FE2CQlen{Z5FUkZyCgl+yobcsmQ-5-?b$`&xXsf_?;|r3UWIXVTzIY>e zWiMZB4YlLt<C^xaU>o1o$GXB(H+7+CD8}fnaFkXy@s&3m4s|w}5@o@z&S(s)c(|<G zR`jU~d!a87ZKGIUIJ7g=xi8j2t<fEwt)}js+;X_BY*Xdt4Xh>#2{SkU)OPiBnqtw~ zNRSa0ujy%S#%s#BGl@j0D_Y+dZNNP@!yh3r4X=;km1|MZYrg2bEz}u`v<7RtIywTK zrg^45E^DIjBSI!-<~z1h!?vBfYP>recHMh#{XM=0pSNb`Jq^sFuBX%T*&lXA+Cq`~ zU`vQ!zoy<jJ)xdZeW)W4Zt04Ie1SG#OmABVN`q~dah8<eQV;J^FcJ&zh}L#>cA9U6 zoA*{<bc8yB;XV^!$=&8l<is7()gId26T==WLZNV^wKLXCQM?r19;#>wv^PT}Y68vF z+!5%-Wp@M;R@1eSP#_k9dt$9Yi=PeQm%^t(CPDNc+hW=%C<a5VkAy5zmP1(ZI#CO| zufj*sSfm}@9Ee6kk=VU~)^>KI84=uz4bfO25+iYmm*0bt;2jmUf%afeJDAEooN}zi z?Y^E^s8?9Qp%99ifdgNgZ?AI;?03YVxZD=$>Ir*0o9+*ENXXmN6bVJ6EPzV&cwJt| z?y#Z|3hr(13P{Bdz|Ys`$^{sYat!l$6T_Vr*>E2hBH8hN3!Z_G34A&9l!|N4PCDSP z3f!*$lECde-*b>(Ddrcup4|es^Jx+|>z|rypu1h*i*0yJkyriJFK~OiCmitCZF&lX z<ImaTCH`ZZye{NZHhGEXVqWLO_O7%p&A)R5&i3A>;7bKw1$>o)7YTeB@ZVSPN=1+A zH@VKSA5?s|kY_%t6+OH@b7Gvoo*`4eqJN$Qk;etj`c=FL>jo!#yX69B{c9}|^Y2Cl z{{sc*^@kJ7ud^=AzvmQuy@DSSMzVaFg1;(o_OsZkn5AbFT=oC=1<w3c`PT)`{laG~ zna&BE+bx$M@|1#aQ1Ch8sKxRs|J4roP6xcj0gpT2&pF`d9Ppnx;PPl@p9ehR$i{wC z$Kyr^e7nHy<9(+hFI;GP&!@<%@%Er1ui~Fk<e85gzxWQDnIun%hi&q5{3dPk5|>A$ z8GaBOI;r1k4PSh8!0{bTGtKaWBCq=4K}CL=y^6ew`xSZB4^4`^ipOm7(%y46d5Oox zAYuM|xm_4MqTnk3=M<bT4I%%$z}auA{Fs8P^2Y>j_x}k6zfI`o>?H-~OL?9@CvYB* z{LDk9w{7w*q9A3%;{v~6!^Z@EMbUqkz&P{dTQ}V9Y6Uk0ZjYaXiu~P*{PPOFR>3!l z0|)D23bJ1+1#X|mwg}ulkA)Rnov-Bc0+v_#oN$m&I^eG>xT@!83a+;6x!E#O+9mrj zCU85S=N#m7=URH~@<jr-`~Q#we#rqZ5`&QSZ&CY2;Ozff6?}`prCnp9Y^S0}+R8;E ziad{BnT{#)YP<MdBQr6dQYno5jDoA{eoDbrd5<_yvL3Zx)+zYM6#ZKr@D>NWSHV^N zaRpcPKj(m-P;gbxNd;Hq?UI74`g7-7#<0CAzRm&PqTp(~TNPZ@^BD)cSK#(I>=(Fw ze>kM*QTK-<4tkP`yc#EOEBe*=OeuPJJ{c2zd`Z!x#^*}$yhX;doIlsu@VL-ZE^zkq z#|6fjVUw47w%hQysI${SPrtzJ>ug-$_VdL-MP6M;o)b9RHEo>|IQNSoxN!D01@|iW zJBohxr?l&WqF=>x@q-DR>~XkM!PR(Mt>9|BZBg(VOQreuGYYQi=~Zx5&sQAqq`>X| zIitweD(%XBgk65MI9J)%_jLkid3D~~?tt%9^sqlqh_-htxC>aE3y~gF^r-TF1y|+6 z0_T3&Y^gB+4hh^IS0e(K`z1rvd0x@a?MnPBihgxmoKW<rarlzJ?d`s9lb2)lZGo=< zf7T=MOE!5ylim}!y}ydYb49ydy1-dpwM#y?l;csh+biVleB|>?mKRHtNohpUuj1cU z_^5Wh>Y%?@JpYvZ<#_D3;U|S7;sTd;N%<igF6EyRxP5;6v7%q)`HsNte(;Frv8?A4 zvQv<+6S$p!xeb?mHVWL%ztV<FdHiOane6=K^I?82q4J@!XkSMx(1<)1vGNvq6$!Nm z%J94`MrBQbSb)kJ@zks=(#1C{zM-sA-cngG*kKk2@t_sIT%nl!Kf2UW8<gd7c1o8a zu6)8?Ss=Ct@|Kq4iu=o$LadAMHY<Ny%;Wt3m)uUS1>@(eth5Rl<Kl6KK(Vj0wJQr) zR!!@0!#eHtpA+@3sKP>4g*M=Zbylb#u4Vln*l@{T@-R@&*E|=hsYMtl|KC=Y$@=ns zJ1)4soqw;WU$9b2TDiUcZc)E{x)>c4o0+{fT=G_PJ9n;fLDa7l|1ZjORw+KRec69( lpPf4((zo(oqFuH^*{)Se_(8B6*WWIFSN$O=C~|xK{{qDWQ*8hM diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/nvic.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/nvic.o index 4b12e11efccfe6a33d29b2460e6c9234bbbea697..c895b19d8ef17e9261c943c5e6f2246188d7670d 100644 GIT binary patch delta 236 zcmeyt{ef$OhC~4~0~|PjSq=;w4D1XO6H+FoC`>%EijiruBBSW!97d7JGZ^J2w=oJ$ zKEY@*S%gVM(g3Jlh=Gv-M1ueegko@-?8qc883^QoWCNh0FxlkEg+SR7sB8h6Z2RPe zOxBZMGL=rQWR{*hlR1V_dh$<Zdq%~{l`QtG>Oj>TlWSS*C;wrI;cQ@pXl9$7$g0n| XfC<8zF?lAdIj05GU#631vd9AfCj%#) delta 380 zcmeys^@DqYhQ$tM1~_m4vm6*W88{dYFvnk$S75#h!$2t!7#l=SbV!+aWYy$0Mxn_Y z7$qjpV3cEIoxGjVl~G`_BBQXRAyB;#10#b1*hmHj7AS2yS&&Iw(jO}8fF>I^*%2sP z0F_NZlWm+_$Ry4<WpXEzHBU)qa<*GhYHCo3fAHkPOl6V`3<6N)Qj82hAHcz6b7onV zqSTzk$-&IAAZI8{-pFh}c>^<xEr{m;R|sJwK*K`<D$WL^fd&FY1Oi~<YLh<#O(|eu tnQX#h!)Q3UkR_gT21p?guus0pqR+X53Bp@CS&-G7vjS?a)nq{yc>p!eIE?@R diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/ow_syslink.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/ow_syslink.o index 73b818d0bdaca516ceaa06e5ad0130ad64c72d49..b5b39e8654c62366d378de943e3977e8e28269a6 100644 GIT binary patch delta 2029 zcmZ{lUuauZ9LLYOxl3<ulK#m}dULm|O<f0Z6Xu{814APlxZ#j?Eo|V1xtKd!)+YTo z>`+M1f`Sv9{`5tZ%?F`%B9#uG`cOr*4^y%|jJ>%rL3}Ig3Klx_oSWZGeqQiG&bjyV z`+m>wcYZlH**v_SS;#2sUA03!=eCCV@<58kwjQ$DHHA-Y8*C>bp6|bZZ7*Z&6VBMe zyFK~E?T0Ma$5^ePv)bc7Sx(082aK=f%vklz*6>Tq+eUup$=e%C>w(wrLMI=4Gt71j z;pZ%$>#MS%7b9%yY0gGw6jlqc>K#RVxcC%e`JJt>^!~Uc){AqE)f825p_5vf!_!Nx z^ichx($8<eL8Zb!T>VOEQ<Ts@@U8kP-(G#91~|V7Jop;_0xkrztKS4qaNZ7mnh9x5 zjVes+53d6J)z)hraG&;gusI)qA?;;Y(USZaJkU&jT#m4zC9U&96BFwcQ0vWaxVo}C zzUPjgy5q7O?eEdGj;=|Ze?k5%7FI<58}jSOuOh$a>6HdZVf=TQWl>k*4=v7BuyvD1 z<oJ{&1hU-0K*R718q&zCDtxBz@1A4jw}!9GjE|KrjZE96nTyUe>o3Bux(Sc;G@K3R zjJcu9&ShuVnXo5E%hS$?eaV53!&x{KKJv=(^29{BG~&$6ignI7c2P`cr^jX;){lkn z6ZxWeFQ*LN8-lBZ4*-vtRvw9TwUg*cI4Yv!Nc`SO>E*LvM@)O3tPmqBTqj%{*5<WB zc)Up&Tf_UkqLKvRw;&WfV(pSBT}^`rQTYvs5k{jCaRfh#ng^-kq*za0a)&fu5xx`7 zQTVdmw5miyy*H)C`iVs83U$}JNut!N!O;%WO5*YH_csN+!>pVpQL|B|JDx)>``$+Q zdBWwdh<6o{Cw%%*<T=6jd15h-H+aQuN{R%kB!Nskh_QKJ0*_zy>Al0Y;M04219_vM za4YjIxYE&EkzGo*Alv<qycJOK9g})mev0t@Ejb%NF8fLQ_B`QYyA{@nrehfJH!hFd zYqY07f!trvJV`)bz7L4L^|Hdxo$VER!ahe?x2T)imypXcD6jtye@xQRw>*MoSvH>C z9=8L7BtQ*IFx6$AS|ia`^^9#0PPb7<?%&2exZP!P4StB3JPmftv`*t61S!a^=N%b^ zw6PLhqkkddx7dJ9BdPzbH@>*JAjIO&DZ6`Ms;wIe@l1#X8<7mu;@Rd?32w);N+}3> i;)O&VB@DZy2}cwzBo2q_p{6;J4NZ16o=(9~y!T(vtN8N( literal 5616 zcmbtXZERE58Gh}X1xgsr7omiVTnbE3z{^LGxDndye2S3{u)Q@}HaW(=X<Wy4a(z=A zWm-Ij)=K3^3{l6AN_1#au~li6HoA4wHp)JPru}HUt*SJn*$G{lG)<ZUgsgSF_r3QV z=Wr5tKX#IP&pFS1&vV}QIqy05dbV${-|27wFAn%AtoAqxFwwBuc3Vw1Y=TFiIP<e? zQGv|8VQ2Pm3)DB^^=qeNGXMPL<|Usadv_5sICL)QgbWUwzp~SPp`bM6?k|Ft-h|^m z1dZ^#(wL*#taq=#<XJDZ9p7?a<alcp{JQ|)AGzYzzzK(!e4gyR;qGj4=H}JwO5i>8 zc@D?SEiAgVT|jdo4{`vcy|V4>70_g?RaO2%S8?W7Ry<2Jup;{Hfb_ekkxRvzct`4C zrJz9WI>1lpnSz&-JquzCdBu@K`~ul7)woxRGdHecyRpoV+7Q13(BCwi`qE~Yj5shp z)QPm>e8k=Q3TPw9Nj`HP6KxzDA>*t{zsog3-@NkJG{!2A<*|zKlCRc!VN9r*6(eF^ zs7iaEFO|OE+5*Os0#BrI4KNPW+O4IXpoxC+ae1ZT3GOSc&BOEk($<&a$6TQ?jmSs& zb5GE07io=iU&J|{!THhF2%<ipHlLjjzp?V+CDbRcY|Xt@jT$-Zc+yU{*7~tBxwPSO z^S?@^ZRA(!yN-AA0Y|1d<H#0!AhYB{KZccTDd4d3lH!I9;HUf|KNkWXE5DG-%C9{3 z8_?JLAx8#215a*6n`=1t@@`n!hV5l+<2pAk%zCtfvMraahPwQWNBi)MM_Z_YH~*gW zXn6(R{2<}cZbv=Z;xmYcJgDs|e=BrGlRKgQ9~gf@Y08nlfO$o}EnvHVaXN}6KaC-N zdPaWnabus9{L8y-zT%80yX5P}7<;l9dxqAB;-dIyyuEi|{trx_;><6s_3Fm83S4(g zQjT;Uh5FM@XN@0gS~uGBwBMIQO7?-G<S1_PfpUuH#H_P1dLP%ayBho}(W>kU>arDe z>v|M2v<@#h8;(10z5iywq#Nta3i!XX1?ot@UC?lRsUA`vd}8OpNEP^ReA|7oum$(I za`;7>YbDy7{a?AU9O}XS^E)d)IvXJM4)QHxPG3<lKagh@^(-jOxe?Sk`5e?;!;82t zKi(O=hWaPJ2=zDrQ$qiHvz_SsZPbX?p8AEdUO%s>m#7ux3F)<rdXXMqM=jTC)*O8U zHM@bDVV!Bjxjs4oD?>`!``0F0w_c^;csKfAa6b9s<uFX<l^wZ3)Q)oS9CDsL>b~#_ z+Wr{z`(X#9XpSFjacd)}@vcUwn?nsgI^bT}j%&ESe%r0ROnZy;qgabGzqd5}6LQW! z3w24n-e=rz3Eb1jjl2fFQ2c@2ozZ!w;TUR2b7~mRBI-tM(hq%u6Hj-kJ+ZLbmfAa{ znvs~Em@-|PY`i})6%VU>!@Tbc1>@>)zvtLsU+*^wWaE9h5ebgl6v(pXpO1e^k9F-0 zs{^_jiH{~8VjAe_=~DL%eC4aEKam&@jRhldbu?k9=9sQ}4ow(|(a1QqjL=xb)I;W! zp{ts!<4{LiyXI=|Q1=Cm*dc7S?cYzht6ilh?QI>0Ehj(ahWilkRaaWiL|OOE44~lO zdPPB|^@@TAm0Y%1z*?L(0IV}Fo*Cd2@SBz$fX%aZ-p^YstGLSSzrb+b-^lQz4ByB4 zqzf+!RP$!J{xY^|%e~dcsS5Z|1^n3xc)S9BwgP^s0{&_R{6~n_qn>YLO=ZNo1H6It zdU4&TfWKD(zf%Ffhd9mK#sofxeJa)1C;U3Y!!`_`Wq6y@2F^2l8@Fe83mdl+>-GFU z!0hqeXO)A@zJuYlEESJ391>>&$?4>HBp!8zU{4tKq!9Aih~EgtlcTzU2%a6?Q=@Pu z7%}@3hF6~$pGLGdXa<iZzZM*igu&zU^?Cge(_^8DX<(c_Jsv(83`KPlp6c*J>eQ4z zrTg?)aAGWB=>A|-hrqz#iEhte;6#7Fug@Rwd%6ev0uV~XlZkQt<dlhrgaP`55s90l zIOVZ;#N_N&+vXh5<9IrSdJH{i>TDi{kq;C>A{I-;ts&(Ay?Q93Kd0kUI`gn%XBM{n zdeSV9VjZs@B&MegJe=72>|u2S>bbfL0r>vfD&Ys2{SL(KJ#7QM0{$p#Q#B~y;(F6Q zqe49PSz`BjJ`qkYK3-m64f0bwjd-3Bj^9(|GS6D%zi3bUkBWvkomITN%o;Q=zJtr< z7Hi4+<QXpObDQDBW4*Xo|E_>P#@bZXq8$~o-)=XpyDH$K4tzf}<MU?0p6>_Q&y$Qt z_LDwbsmQp=aN-yJNma0af#Kx8xbAZm>|bZN%>TZ?BgT7|;c{FL7~X`nn76g;oRRhH zWw^}a7wpA(@%NThWPbc@V-=bI62oOZuL|~}KCe~aza`kW*i%{eI}9iPDW7=`{Zqij z{J+a^@<+6Pz;HSLKV~?^CFXxEJBRtaW6Y;UhI4+7w@CJGX0J;293Nu1?9VqCF8h-b z@Xs-Bs?Jy7nHTKExLy<RR)OcY45xTSJ#Pv)>B-N>KQdhQ|80hIeYpLf87{}w$dXvj z&&L=}_TqWFN5I9rJ;-o5Z;vos&d-qw_&I@J%-fd*Ts$B00xsGgVTZ3A*C4~?xP}B= zjBAA9a$I8!m*cur0e@ZK7yY~?;9^{x*(W9WDcXZ8IUO^Dr?EB-yB^~$Lmv;iOg&|S zD~ul);5wa5g3Cxyhs@huN5B=r*SQ`yh1C1MnktS)7uS3NyAh)@D191>?_zqs120-a zH(p}7Q)BmzY_MypXr7IBw|oxS-|_UD<Kc2%nwLK%4zbX81#!yb=h*oDqA{}-p?2&L zXNL%4n~(pVgmeG7A8ve3?Ka7-iN!rE;e4D}vm^8&%M=^m#sZ^xX&>|X`8oawVsh+6 gbk+X(3SE360<lP4>l<pl@hUsSj@iS?cX|AO0m)ZKivR!s diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/position_controller_indi.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/position_controller_indi.o index 6e2ce2aa138d811106f568b9fe84bca319bd25ed..fc0b9d2d2d308b03de3d07509bc05d1f0afb5acd 100644 GIT binary patch delta 1914 zcmZ{kKWGzC9LL|&s0~JG)%J4Ne-{kc)D{#9MyMp2%#gt`bV<+}JUEkRGGr*E!44T5 zD!-0h3L*t7q_jiEW|0g!2pu|P=-}X>dj|#I-Fwk*+P)jU@7?G7`*Zj1z1v=DF0Idm zn=$t9O8T=TyUwn$-F#~_5>VEr7;iAnhSh!Of}Cv8yD@`*@HFyK#n{U0=YCfF-d<zu z1&@_W6{qTyiaDpa><DqHxq{<XpTDlKm$}kY_N-JXu!>VG(0tgSSh!SA%3f@oGiIu} zH)J$C58P67Z*Vny1vu7kN?t$Hcmoo!!47aN)CP|6UEmmh2;5?i)twlQ2aNyx1UME7 zh!yiLZ{;ldWEypBA4OLN`nsUuN#NKeqv6YEdEIYN1_K{xRm0zE_$F|Cpnc$2zss-6 z*Ocq=)iO*>`vGYt{jrQk==Qg@C87*it+?9mHwEu+dCy*?#<*c-z@3DwHQE(!OSun4 z?i9F3er^xkX>f;VWWq2*7bWs?ZEzPTCEU1jM}@1VevC`6gj<8$2;{ENmT=d=y$x=f z_@rTWFG+OzG#=8o34<T|`qR_;Z%w3q`TPoV8osFEPk`fR&Py)OEgCK);HRwt$M`02 zjDN4;`vY9=b^lclz`zDyG`y$bC&2N60$0vi(X3#%z`({c8XgCZ4bsTz*VN#T#03|- zG&Ot!ICk05@HTK&pWaN53>?oM#9+<rkX#z?m_+5&*CXP#VSW!vbo!Wt=)P_6sHb~* zdppQo3eG;@HA>AUc#9fB%hd6e-%aoXN(oI;L+C1Xgsu~xOYkhEgtn<6G)*0$!^G$B F`~|iBjz<6h delta 1986 zcmZ{lKWI}y9LMjOs13H&s_nfrvB{$WTg}ixu!4{`bZ~G`=nz7|1fir5O`%J+S3yKD zL*%z)=+Hos2RgL0qk@BogF^?EEJCwI=puCJ5W#zQ7xPWx1@gPQ&-eG|z2Ds>FLQpb zHn-@{vwt5~&RjOm#uy8;iyuReek78i@4<I)z31*udLugYg%~e0i(S&|E`OzYQuDAL z-)O#|*Q00D<gMneUU&UJYyLp<yQ;u`c`9c`9+x*(*~Z$_Rr<mm8n>q?Vwb(V%E)3C zV_eUJp=98jz->JbhN^*Y0muBl;@(i<0|>wZUx8zyCUEp`14sW8;CA0Diw*>zpc6KI zh;k3ZQm86NX%`KA$-tKlJP%yg^<;t4ups$!1Fr$cery}~I|F}jT~MznPX_&*=21-7 z#xNR-@h8}=5q$s$Pt{ce?;hl7ku|EyN}JXGR|M}K@<3RjLX1aCpk9Nh9eOR)L#^Hs zu`{5a%GeI52~g+gw}?%L6bfRKpe~aW=h3WICxxn~(x*xfg<6ML2V%GAnNW8?odvZ> zEups0Dm2))6WWV&kDcqOxEG@a9tV!Q;~MyV17A^m_^z%)06x&Bfmea!1J!|J9v?Vo z>ORO8eCiW=ZTx27N5HYbv4MB~$Fri2eZIE^_y#EhzXco%-$PD+X8M0@ilAbZ3UJI; zHE`d+4}k0ZM2U&ME8GMhtaS_=pRHry75yg{T%}ZRr`RdA65I;YM3P%+X_o@K?<W0- zRi$6^x2-xkH!{{C6@;x(L)w<GN95ehSa~W4yG;#Ycc~?8g`9N8YEnViA~l3vpjP_& EU)EcVng9R* diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/position_controller_pid.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/position_controller_pid.o index 537a71ec57cf7a626a10a95faf651f54b2c29fb8..123e9a3fedd8f76f3176e589a24aa02fe0c26775 100644 GIT binary patch delta 1132 zcmZ{hF)RaN6vw}>h^t6kd)IzFitFjnnwXf}5rc}sh!|KJO++*nLlc{b7|QFw#voC# zNEZW1S&Z7f!wm*C84V=vyZgw?$=&e2?|%RH{`cO!^1PiZXA-tf{vOM{Swtp%<YGG# zR;ec)!efMKC(cWhP@)T37w08cY0ZrfZhUg%GmlzRRM{cV>rGU>a<%7OsEtloiJn1+ zve3PgCp(3$JS-?f@EuJ+Nl9wDS4$M9xI^6ek%n7^?ac}@;HU|tZU*p50KW_1tpF~2 zql}V%--j(v_}A_%6jio&DpcNXzp&=V72*Sk|Nduxej_0N3-KiKk-QDe5N<Sx1YNAg z&&LqQMsv_q8C~NsS3)^>m?OmTFp^lGf0MoN7-LY6Nz1$o9d)-MDmceoln}?$*n;z= zXvjx}+c;a#bb5%p;eIC($NjD%j`KGW$N3fhmD~+dan(KIxT+<%|F77t+Z(Df&_o{r z{4;<Pm}ZPhZcNlJ*h`oup_rPW8&FM|&O+NMGbBrJ+!Y7Q$WR#yh8g+{!?iI*51?(B oREO+{Nw1*b#B-=RaTnSy$)-)my5Ph`sHV;ElJ0f7597x04~UL%zW@LL delta 1169 zcmaixJxE(o6vyvP45$cs=ELhV)g-SDK}2*i5%Il%gBFDd4&C%o2rcwO(IF|6Rtm+z zA#xU5Ty*N-RtgO`NbBGt>Y!$DaFpWU>el;ll*5D22k(FH`<-+C_uTWYr)$q@xhX5l z9v@HdJZ7;dV=XLt5MH=QXTs;|{onVF*E!dUP8GSv7?(cgdEg(AX9D~)@?qo&ZZ_Xw zvs2i+7%d?^!1bq!@;_RSl{%N0X@yPw4QBpD&LS`n`x<@mZl%mtUcD`|@*BTWhTpMS zu;VEhix1f)Q_1486kRl#hqbuyS23EB(G>30vfYFqHsLo-cn2&e#E6G&_XJK^LLTgG z6^aQleS}ffTQB;nr9pTf;dg}7d<G*)@o_L@Qk9z^Re8d@2`@F_i-c333gKzuQ!_lq z)WI~c2WJVv_f>Ot9{)^m5aY0!6#i?BDhHcbZxK#g*(01@$!amh>Nh+gK9jK4CH&_Y z4UYRI;dI;^gwt_v6HfCF^(j{*N~>-Or&S#h(`axq7V@OL3tm?zc0*AJp3$1qI;=IX zb?V2mIBDZEP|S|<EvRN)UW0np4SB8LN4mgra@>Q0<A!qW@ZOo=zo728yae}B8&G)a i@>8fv{SI}h4Y-$@heE&0KS8zMZClTncE133(*FP+YIiCC diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/pulse_processor_v2.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/pulse_processor_v2.o index 56e35f2d43605b767069d408215d7646449c4c09..a69c683d31581c8a6d4035a69ff96ca85ba0f07b 100644 GIT binary patch delta 308 zcmca0HG^}4hQtge1~_m4vm6*W7}yymHYiM-Ai%-E&=7QhIsV$@AFS&bnI>Q45}mw+ zO=R)~Ho3|B*n}prv$zT|Fv1OBfwHWDG)P<k%7=-2K*bf%#8W3vWEY>@z#%#LGKc<T zZBE(Aah&p#JGrF!OHwOJ81zySOA;CMl8TEbAK>zu9Kg*oS%h1L*8*w^n40{NU6@gE z@<eWN#tNV_#U~%&7GPALd=ZH+GC71tgsFmIau$!B=nbf54yfzdfPD7JdwH}uA3#N# SCx7HI=S+r%kLl!%-0}cztT{6P literal 3408 zcmbtXeN0=|75}|=4R&ZEKGS3&!_OH_3>p+HD%IVlJloJOvW}RyC|jbz!#oPJjlq6Y zAktu1_7Qo~;-+f5F{w#6wK4st|3t%TrNEk`-7<A)x=#CR0hDU%=%j5)nz4j==bHBt z?<GvycF^@X_jk|7J?EZ#Z6@0GJSqwTOcL-j+?kmuaIxf$EaycTCD;JiP&&uDe(RLj zhkX3E^Fmv0Z=J7>XEUn|>8qVW<|-3rt})D9KOkm4Wo+g~h-Gdt+ssPXmiY%0XKp5n zGJo7v9Hs3&?|V&N>6t%z={o5P5H9S7xcqn}6yNLeiuBgeOQ%KQ!Wj|E?g}V9#d7wg z9Y|y8NRXX98gx|duk!)-xnOH|9Yn=$u<*N^pg2E^VeuVgHzOHr*a+q2Un1Lmb22Dx zI2HE?Cxbu#%WLtiz_G2gUk7&8JV8Ss-D(<M8bv_W@#g|w7s(T%5I!nE*^SNNa4x4T zu<H7&oxaTV1OCj7P$07sZq3|Gv{62fMpwt*ImPQDuw+m@d~#ZXEu9pR5<6sX7b?R- zF_ft#Im^oAtly1tKUlk;_TANiVRsRf@x$`*DKQzWokRLtewG%;$KUGt<}1_Ro?_{P zv={&HT!&T2+3x<{*-#nMXTX*ZzJaX7_pi80LEJ?;Alc<`*MMZ#)*UtAGI7_#ZW?tp zAP#q3jcluG@Si|hUCk-^vnZ`jeSzXgKg9~q{R0u%6&eQvLUt~f+cL@b#FCe|E?<9> zFy|%=(?KfEBKdEi{CLfIy&c56>AXPa0IJ6#tDMQ(s?s#K$J?}KLpk0?_J`!BxCnbi zvbhWlN2uO^BJ6?vve)lGd69?~iE7y00k1?@_kMUULku_E$|-?E6UReyJ5sEarCQ0K zM(dM=x#nt9LaC7YXf@Ze#BBA~$RFSH0^2sj<40*O6wG^R?s!(L{FrT>nR-P?fA=|- zE}`|EG&Ukxv59g>QT~f;1KB5o4;=A5d`>#Itqa2P37{U^QK3?QIKPPD#Tz+AZW7*K zbS8tJ0N&OPq?tqZ?!Lu_e*&~DP@NcPPW?LhDb>Ck>6d}!#ee1$uCs7Gr}$*y{UVCX zV||X!{EQ9FF47B;{YMP-^Vi6Z@^zMBSfIFkT_WscZNv0a&rTe_Li>DgzCOjs{=Jon z4<wtMZKA#_7tv0A6P~2_zn*uc7DOnMwB{0p`}iGF#~z#wk>4W}Yl3{Aq&)#;?N1ib zS<$*vC<)h13Tb~*NH5GeXa7KYD&_kS#hJ?2RQ4`X&KF4j0mYlA7_l+e>@v;Gw}<o9 z@i*^!FI;qXCn>+~pzP&m<FsM;W9lu!ybG*qhW8M^d#mH;PSF`wJzXJZcja;|{GEBB zL`pdh{V4dja3VfJefJBGFMC?Fx1at7Dqj7%ul)SnuJZHP(0-nBxC}?wO+EIZN62!& z{4VntR{!5ANe1nn<Rx{V>|H8lnYryJrmt+VW%!-uJtWYXFO>!|SGKff{%pyQpBsM* zHtw~f_RDrCZFU^_k{v(x+VQJqJFYa?ajVXbs-1S|_uKJ_Xvdzb#W=KFjI)=EQG2l% zk+a3XV}ZaUlKZizzA7oPSR~Z14h%|tvACr7Ym%>FC?4w@h>#Qy^$+M;NFRx7lDE;* z;Av|1Ha2@Cw;GQ&kknLH$MMEyiLW#_c^;w+{sRfLX2V}|_flc^{N@1|{oRWgd9u>| zd4NZ`n;7T?w$Nwt^SklwgbM}wa)BMA2gyqH1XL94-(e^`Xy9eW+{9Z9T(aPg7<iKf zmkpeAPG;tvB=fi(dGroGV&L5dUTYXk(cIjNv6N@W*1=y~2Y;P#9`~5x_cwVjz`N_{ z|K89aGD>aM0Yf8^gw{p<7Sa-lSiI{QPh$wRqp0mg;A??BZCxF0!6&}b+KEss(TBvq zU?2LT>L`iBalH?t%0N_$2jZHlYn{5P4}{h{c9;(Lc>=M)XSBGk#P&7&2A_^-3G}Oj zy%Eirj3l%WcaqT6=n$e>G&D43@ezn<YTSbD^B5sIcmjyU^wCx=6zkRE2JRow?=o2n zxpzd34CrI|ial@Ct(sc4+>kjdGg`Qkcwx6y8Te)kE{SW#RzG_RaC-D_)A!fGHyT%s z`>DLG4QyWrzi6EQHqtNbt0v=|t$2rlbN`zQ{G%~37S+`r;(C0I_nT5&i>QsdHmaks zSJhQC_9PN$jK|g{p;$Dk4eEuy{tsCqTiV*c)ttMN`3KRc<*6vlnXgyV;3bi16jG9Y zDsysh=R|fITr}?i{cg<DPWt4y^~IaD#9h-~(=}zzKTm`E{9o;x$(F}A+JmGuGULl8 zU~qH)ChR4F+c%kj!T)aT|9}POx||BRH8x-0Z(IVmvB=}{e@V>vX8m}Xt+^9~q@j3= aPYTG4YeM`E-pl@bJQ$IGjotpV+W!ksOpdq! diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/radiolink.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/radiolink.o index 55639c9769b21bb2384da3f0d8e0f8da02e1704b..4d46204d37108766e1fb7c5f133416dda8d59a66 100644 GIT binary patch literal 7960 zcmeI1e{2-T702KGh~omK4kkcDDwg6<6TxwIfcPqC_WT2a1m(CpDil<m*LRD3;(T}B zT?ad$_5!p@rT*b-^GDj|50@Ynqx@m1NF|lhT7|Zj8dWGtBcw*^QJM;={eu)pYbh3e zZ}*LFn7fr4_1_Hg&CF-M^XAQ)*}1vp+XDyo1_J>QDFDBKdQDJ(qwDKs-7V_y1y~6h zRFZR{%=;U((4XiJpt4G-Kh(Z>>Q^(1A*kM64hwffa47(K?70aTn-4&GQy3n51Yqg{ zK-Fl0>d<NZhm}^S{u&^5HViQw_Eof>yt`aqSUmNci!=`UI)!{{Blf|(+Pl7zB%Kk| zWB+{cU@ewc3*RVTJoU?&jans1KGaS?td@o9&1Ybe`YfLMooiFo$3K<+%FG+np8cC| zK=nLS-mR^Lh1x%O&bOd?%l5{rh1xICxZZr`-LV%>z3s&(6_~l-4h!u#xA7oUr<cWJ z(*Qf}rsBwH{#RZ7YHWWM+i!(dUpmtptj1d_NeyE}cEcFIK)8}TI~1y(IsZs?8u^9I zut04AZ2Rfc=vM%CP~Gp(M%!eM#vEK0h|&0BY&G`572dcMcM(I1_f757#QUwK`P2RY z+#eeN#=`6NzEr_IvY`#e23s)igfW`Cwj9zlfAX<%KFI$4-i-~-X%P2;_9*PUe=In2 z6XQ*NDyR?Px&-kr*P_RuQ(rh2hQl3CLJ#%X5QdM8Afz8h?Q~Fg<3)W)-#!?qLWjOU zwuE*tRQKWjvECWg4>eBbS9@`~jd2qG7|WpgWwZ|?!79y%Y&V;e@JH+&8gGu`y$;4U z{`*1NZ=N(4nyYJDnXj<vu5%Or$tLyx_$uy0j>iz%GFCx#ZY5N+E&60{D;(~{J(Ug5 zy>P2NG(rB8=4D!&gud|CtN5&a{NQpewC2)AtZVSx`{a97+AFkYC{`QsIo1-eK+pHm zd4bQv(s^+Q#xCOe(0MTss3gPK=Nz3G7(@5Wn8z5-1*_kg3&ze~3%ch<4WAG43IFiC z@Ya;(>+R>}XUUl_dFy209{P~|^!nqx(KjqZB(i<PC~UW_>~_n@<x7Qp@kAsGP~P@6 zJO7fY?cSsHCDVz_!T8Zke>@$}r1rlsfc>(TQ%)G!6Q<K|7V<Be7M(ztCJv9A<7Ub% z<~kcCTeZ!00WBBI;;=KaRf}%X_UzHhxkNmb^1938Cb}Dk1=mT`TDG01E_u7JR4kfV z$IQ7FY^PMt2$4%Z`}iyZ|9b>p_L1T<-8A{}N>eq$eSLjj)jIcm{fL$>l?vGrBVW{x zmn_X0F}3)%vQ;{sFJQ^aj^rKO*5j6`#UkC?x}#mONLRPkX;`D%uoT_0g?OY(qn55{ z_fEe7Js!XezZM=eQ-zw|m;gffuUQJAB{hBC1vJXTsST?^$$l$0KgFEdDG9D)ne-aw zlmw@82=I2LB=6j4<ljIY*@?2g%(<s;^uLJh0cl>ntUt+I)Wr<H#r%2J2|vHfJfZL( zF+a*&*!vmtA2S#B-()_`T-bk$`9<bJ|6As>%!PfbhM<LMJ@eww$p46vfTW+|E`MPz z>caj#<~LX;+S|}EvNOUCPIEhDA$U}(c}35kMjmzT)On}WGX$TLYO<Y1zT34^=Yvwu z5G<E!UU5I_+Zrf9!iOJ2z6xhN&3(iU%lqiZSwGAA4$i;lqyGu(Yl?oBImMfj?tTJX zV^023n)fnz7wgUD^`Q^{$cL{8Hn;PX57&`Xd^F4{iTNI3o?w2D{Vig>nV%IO{sSM5 z_pGLNe(uBH_Thi<;Wv=eyb`?N!sov;A7uW0Z`#m;M=I&>FkivkyV&sUt7D>G-7j5m zmTqWCGi&0di*9D#C9JMbna)7b7%G_1k&|gLC#mrk7TNji&RuwY+F#5&;CR=zX16+L z!W#kgJ9c{4u5x!dlQjy3A-w-RbOH0s?utUmPEFbwwt8@Q^kI;4N|rHfGHkpi);lz| ziM~srI8=sArcfHT`PMgTj%Le~VA!^4IeU$Kp&o>^X**y~+7xBCykrD});D6{J+dI$ z=?2>*wEc!-ScYTPjbhh$E@zpxU1x4gy^!`<CdyNe;pDTzw%eR76_4kKhYF?aiG8M% zq`S9pp-EG!Y~lsCNkhZf=ue__(zN=AM(YmYYS5(n^LE*AvLi5&Hf$O;ozI@=D~%T& zzPIl)i>8&&(&Qnt@4%tn_<_u!y?avw=}bD_dte{~wmFs|Q%A~BFmqT-ju*KzZ^|V} zf9YfqaIYlI;k@mbR$s5=5QVp!H*c?1GICi17iVcf(6<9P3ZA$8e6-`az>kbe(##)M zc#ioRg%_BwN4|;6lvTJ)_Uqpc0Ou6Gj_a>*PUFgY@q7y|^z?&`5{=v872VHiE<b^M zv&6+YO?vse?mw(ic@OF+sq@k$F54MouEsORT#aW%(y#G`azD>WdYQk*oc!4;=`Z_m z`ktah`fXm({lxcaZXzC$_&XB+io~x=e7nTollT^i-;j7z;vY!-X^GdEtMU1Sxw?M< z&womS_jpwZGZ*`WF|;aN=-Zf69OV7eBXN0sPcv87_nc%uEC$8=b;-^%5})<4bJ@qv zb;-^S$<7Co9r-6pjd={`wM)|fO|tW>#BVcih`*#4F{5s+{L@9%cQ6<0B8KQxxHxyV zN_OPuJ*se_?_sX4moC|t<KHjYk$KvOAC>HH63$~@W=`>>7e*pEl3tGIX^G4G=QZZ) z{&}6b8qbT8US8i>AN?G2ijTZct}$2l!@Q)I{lCqe{FKMN<74NZkDYZKbn<7D2pZ-Z zb9KJro~Onq?W4!{vTjoKulVRMFjxI~Q{wV^%}Vy=I9z6~?uRRq9XX!wNOt6XeqG^H z9HaM`Q+#Co4TTGRjk)?<h<h-_=Sj9r**(dQ%!P#h%ZDC)jX^8tf=9XDrf^YTr*N(= zy>B2pG_P51&^Q<T3fIM25GR+#?|5+*3H==Fb<TzUBG(fVr*W@y9U}JRsACLa?pR(v zB1)E7Fd~jQ;XovZ_fm)q;UzR;m8e4Uu1F6=ve{7&lh|#+ZV|k88U@r6#LIKUy?CLx zG&*YHZSen38k)e6NN*B6o4S|5C%nE~ZTO8w|6NBCT?ja@J?0hKc){uS6OAL*U#u(L zsfhDqk0medZhTebHjq|Mbax?}YJZ*k|4SCLRz_V|A)DPY#IorBXN3#@g&#V$H}hZP zS2p6lAk2vVqJGe)e<uq&g^+W#|MSS3#sAJ1y$*xikK#{nXGDJy{~=_}{7<lO5ZmP> z`V00=EHoQG@r0+CVj+!B&x`0U#vesS<45sNPO~gLCPOTXxXU?TEgn*~@nLs`_W`~4 pr0)%Ne3GeqhYZcHq)&jgN~0LpYXzWfu1MUb8qfblA>>@`|6gBZ=G6cI literal 8320 zcmeHMeQZ<L6+iZK)3nf*5*S%2<FRIK=)jOPw3yNH^1;^zBiQZ~K_}<Meqa~JcKlx2 zP^d5;mH4B7U@g-=RH^RA9|TPk(y9%ZHl?N7m{v__>MEpZlYve`Vw#v3t0FDS&UyFT z_;O=QtM+d%vhTgW`#T@^-1Dwa9!ECs*b)o`K(+w<9BMO(0!%(y8(aR+f`{Ni9F?Mz zM&je;rtwGmOdtBy#IynB+w))w7sqcKa0dHR0kF=)E2XF#4E&DpBk!9xt53Y~$nAO7 z)byeEPfHynkM>XbI%0tdk}u6KMZ3WA^<6bu&IAuz->n*pNbmUa5d5QRys_tYtb0P$ zQ}gGS!XMQ2Pt<j%1*XuK$fhwEX*VGLSO^|&L3?fx%14`^JcPOjzX9dZ9w;B_fk<)- zM97XCwx-Ar8ecUQ`#u;@`a>1{ne}4{?g#z2(?WZ?=<kX4g6pSN0F<#We|f3UaWrT} zuFlLXL2QxqRmAVY#0s+%rTteAK%|<4^3|u{AlaBc^y}F;Ntx+G7bdzt6aU=A+ZCbz z>f2C$i}tVtrm8o^nccn)<?F7nC-)}K=#p=H`cN&N6ibTTD8{aGtUFQx=+gJU2-nAP z{W_l4v7TVLySWrKF=uE$A&hk(REi!SGRnu^x~E)0{GG7Kn*gr8*@S)tpo_STK6GxR zk77P}ED#ZSP(Sw9<_Wuh!?>&QyJ~)xc%PrmC)yk3r=L#%BW<l)ULFiUeA5CLv6`@N zhmpzqAx`_>Ff;T0(zPJ__ZvT!v?m+$;8k2N1>yXAO|b6H-rxk~IOSFlKdB}wQVCg8 zCql5h?NL}yGL-Xn5aNr`ekCZL3zRPtzoil=!zycvbV#m+c}_mu+1oSGTE~w7>Ot;o zjviYi;&cP!M0)M}F>g^foDNbBkCU#ZI(nopGH=M<d#GbmD~#Bm&cyY-k^iKt-X5hc z(sA=Yb7M!kNd8|JG50tILl`T2A(ST{gmSXUI@r?;yL&K?lA*~x*ISG+@|`$G(WW_I zO<lVP5$n^LcdN!1&aA+>37bA9d*e!eP;6G<b88O36x~s?_Z#0${@LGxk<)k{beC)n zl%gS&Ie{`1H@Z(s%|>|~jPk2sM2?3H|2~oT7y5*;7iUO$tlne#xeP56=VD{d{FQwa z^0;U84aX1;uSwh4HEuDvrf8=!`D`Y4Ae;m!tp2*2dD$^HK5O<y<Nb-9-2;if?s#`1 zwtdfLluH)9Lcg6n;COvbHuIuWq#Fm@*zQqh)QLH{RQp`YD)VtSi<+}eZoijaWv*Rm zKKra$NcDHeVnSTC+uu3YEci|$x9GYV63Mu|`CQIPdQQsM;ClH&LXv#s^RLe%@V`gk zXag!f({)=Tyi}Ks;MU&W4QBh+Z#`$m^Z9HtZD(@kzI@U2(vI1^x=_sT%Vcp>Or|p) zruAsiF(cv5)tzfQBH@lsv)wKZug1~Zl`9DkcbK%&v9@zvBZC4DV23{gGxb<T-3kuC zz<>3cftvL8fDe$ByW0Ys1{M9yy!;sBv`%fK==>in;`j5sk9+D2xJQ|Zp}05Z;@`$) z(o<mx*$e($|8vL-DEpF(R~VOm%N{RbpD+FI!8x@b;)nDM_%i^>f0OY+#$}{VGoEH# z>iHSt^rK8o@_*rvLvYqdYx*xSevWa;|A_HP#-)Cm8qmaOtrPK?i~kuZ0fkTdr}lUJ z5H9CZzkv=Ae#K|`KU)51Ipb+|u)^!q8E~&M6GP$8Tzr$Sr-rvHk_OzT%v3#d@o)Ni zYWSccX}~;XCWZsZmuIdnzR&>AHNX!yz>hb;zt;e-AifYIZDCJM=Iu`!@GmgGpZRS< z41V8$UuAwt<KJQYEaMjIxi2XExy3l;CAB4p*NfYe4e+NM;JX{(FEqfhR`%mFi9I#B z-ybo4i}4%m?@w`F&(GgBz&~n$|D^$b6LC7PDj$@zHO2TX#$OZe!WZ!hCVq*pxcQ8W zLWrxiwz1kY=6IWP_E6TTLEDuYX|~9VI!OoXHY)B!9S3cxng|te%2L*LJ;91+k_YM) ze^}Rr*FCc?0-mS<u`t`7%Xl~ya=6&_jHucQorOfw&Sr<Oe7viE6FQ#mg1j3$=q6ax z&i%u812HdOwD&s<&aE<Q0&~}->}(iz6(Etw=J&f?G>*k>_rO-iqkZ<~M{^$R?2L0& z%OQhdXE<3n$lz8d=M*zZ3K-a~>lD2$b|zbkWZZE*a1Xk4RQ`C@G@ev%+Q#BFE7wU0 zABM{6vpu_Ld&-HTXm=`AbX>P)$Pc#&es9r1dd#!EOj7Fhmy`M2zRdoiY(7bQj8efb zU8u7ZD>ztH*IAfj8~y3ezvLAAhK6en;Th7V`!a69_L6BxY~8V|r+Y_Y*Oo1@&GAIM zyJyGd1h~#ff@sebAnT-X79Gvaf_?dya)9{~b@pdm&nfoyDC#L#ot(Tq#k`$LVwTp{ zaf3ThFF!Bxb<|RP&gC6IOLE+TI6r#6g#0~Ors4E*fg0)giWvIeaUM%O%{)(Y|0UKV z@hs!Ip2G_MIFG6OfX7n5T)M=A#hRa=Fi!fPkYwy{DY)u?2zk_q-!6v!x5+r!t^G=3 z+%&wEW!f1he^mY|4VU~b#>wtV#jeHpBiMgc!DZb*{M8En1Lo`a6$Mx0P*reM4;GDn z)8iasT#vJ<@ag58Y;6i(#n&@Ves)MQ_VEUIO2Io7ep<nwQt+&TuTt=Wg3BDHWlzDw z3V%$&)jur`EBG3PUt(O3&+Clq`BTyG^{ne1MUR?4_`bw%GOr~6EaQ6qTv2fKeE-e3 ze!gw|r;hIbM#f3Myer6&z6ShljO+JCLD8c=Uxyhdf8?G>e~Ix3;`9PYwiAk;4HCru zB;&gOuPc1@J~`ch{{iFrd0o=*ezyIgqDMWi%Nj2ER~XmNtE%wTd-#^ZSD#;eH}5xn zzw=p`;`TN6k-7zplU+4#tqQK@$wtQYbFmoL?Zy>7>iG^ZuAk%c3Saf-Fyp#ie4pz# zUC+q|dVZ|nYTVvsT=!qrqhyyUzP(Qx@E37Cs`FbJ*Y$TXPVra$*{I-Z{4GVl`dsue zuAlEVMUNWK=M_C_ehzB*DG^>sF;4!g{IrHket~g4pJlyH@ma>YsXL+QQE^G3|61cK z%7>bHLE;sjFVJxLe6?!0<f(dSUuT(TDtyAv@m%IG*`*Ya?;+$_5KjC_=3CrLzSJZA zlKjiegRpyW*t3VQ_llxV%TdwE+F{Qb^B|nU(ig%*Sm%a|d72QtBfK8M$>gwriR`bS zSQsl?JBwTbv8oUIWi*oW!@~~N^8bG`Q3Y;Yc@rXZTB3v3_<VUf=WofSxIpo=B!T;L z3&o(q2StD9ksWz%@?7Z-C!DW89EtX!W>@0GRU6d=q*Ir_%<@4^K-!l&sAeIGT8q${ zl>ZY=lqTh+S_{``tlK}^B!rsP<VQ%#i&cP~IH)Ioj*0D($h|JV4e@&MAE1N5Ht2r? zQ2g)3kCd13A4062{VEd&ab0avUSi+DK|TBD*#0Rdl6`u<q`b60j2PKpiyyUFM8>vP zbhF>YrKa{;i2d~n%irKUcmUBh{OI<Hrk@=tIQbBL13alMO1oke;9(qS6n|+O|AF?R JByz9I{})MeHh2I4 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/stabilizer.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/stabilizer.o index a8ffbc684256fd5fd961b599349a2c64d590f739..2699746cfba29afd2e4fabb1e45e154e9d5e1a8a 100644 GIT binary patch literal 11536 zcmeHNO>87b6)x`pYr;ZI2*Tkny}=?A#E!;R5Do;X(e7pqT9HxKNM-@qy|WXKr5Vq7 zrq|d}BqkC_KIE_w67qqA#f3ct<O2eu<S>UEjNsq{pydGa4Ielp5<)&8L4DQVb3a#i z<2CGMrIfT&^}hP*d#_$qji;;k`<JgicV=Y7NEtD|HmN13F?$nfJ9N#^oHv0PmgfKT zcu@MI{QF;Q$o1nWZd~riOKn?UH)hTGFlL?gORQJfvC58Bc0|M@;t}zcTTzUmJuCY{ zr`4j2vujIny-5K5--^Cx<LGqf{a`HT7z90Pb*Zs#$D*t-jupnSB5@?$Ir?sxsdtuR zXf}GZ<K8?pT|BC@9W6S7!^N=3;(D)x4u^|j?Hf^oNBv~#aiiS@uiI<%`?q=xv{BqR zAzM4D*Hc^!$BS+(wU%CzIOAsTR^Mj07hj8`8^$ax$FrU1Z@HX9!0FoL$)I}NYsFD- zu@PTS^?lIxq>!UA4@ZMdBiSk)rpxsw%>VxR4{q*P3TRK>Cwx$#b6US=3v`O&JgwjN z7U-W=rzoCx@g%{g&1ccNJm~mo^KifR&x7LkY_eT4pZ5#Dl2J~8QUN|Fz)$-<cE8r~ zU7ch>it=#U^?K01Pm1C%+RsJ&)8ePibGhIgofa?hYpz_p_@$tH<s07&W;>l$y%{Yn z2QPMdLELNvU%k-nbzWR**;cRKT#6g@*#7hjo~cY-n5s@bQ<<C!%2BU<!M3VTJq5fn z8K7sfI`xHuzzO5$)O*Z3|ITBTa-SrODVZ~Qbc<(K?L&?UFWFMEp8fJ+2NdC1{YNc- zMEQM$f;eBm$7u(wzes$Vws?Au__H29OFSfgj`eql*Jy)>Vt+zAzjvHvjQD92-zWYm z>s8_{rby!XA@MG8oxzgH?)D^aS^P&%C&l%CEt#{7BCQggEdEoclj3|#asx}|{iy(3 ziB1;(xzkDU<2oNG(8=PzaXKkJqehm@2bGmHlX$ZD@0?DG*HofQ=HUXJEdCd#lj5Vt zbQ14cEJ3pP+fFCNkLTwjTEevxW)}aK(@F8;Iv*|2$>L}2JVs2457o$$`IxejW)e>p zf6VEm`1Y~<JXWBS#VbxH#hb@;K2e~P#V<LX6hEGyPi1uGEdLRk2`O?;7m1ItL-1AN zfrr0Fyz1e<ARc=7p2bC*T}hQblUM3yV$Dq4H2p^0?brwSi=DQ+9%xty*D}gZZz5*b zyN&cI+*#~Q23fV`ey4XSilZZ8dpqDR2d-Mt<@&m5v>Wy&z_za0TNe!DEx`-6-^|aq zI*a{z+&!@At|!<|1Cd^JV<4QP>w@b-ayKLF#_b84scVI#_ffeZG`mqRYWHzpB=;L> z^J~jXv6|DYy|GZ{wMKloX!Z@e5JjE-xY?z4qhqgItlzkQaXCinu67n@qUD=McS%@q zT=9KHZGcg>fv2b37>&Qra&Fsxl)!x^I>2R5$=?I$VDH``Z`$LJ(+(95{_C`B3Wt6` zdrsltZ_{on9Q;kj>Bo<AhZ4BYH2wwRe*AwR&yQceCqkuzc=l-f@pq~3$Nzis{rCsu z`|%s%0mmWFF8{>+_%D&?$3I@6KgOS88GY*b`T=z^`s9bKWj{=i@8>5V&(BYpd_O-D zN7vJ@l0Q&5@>8X~p>V9%)8ua|9DJG2mcqfGCVyMu;D@w#6b^n!{;tBopP{{{aPaYW z1ZCfSru(x-`#|B~&yatpaOg{XvR@?sGJcHXWdBIqvM+@Hck0SI2!BXi@-2MvC-WA5 zz<o8!ae^N(j=;mmXqOd^`AU)X5uI^%gsdeVx;2tN;Roc+d3^EFR5<b}adZ_9F8WXg z?lWDlD(wx0gFi}pQ{m8%`D`g1{D)|7D;)fg_Kw2AKSz64;o#5E-cvaE$@A2`@3%3I zKU6x<Kjb>f{3Oq^4+4)bI%S0;o?p_Ie2C6C@sPEwugt%uaKsbPo>MsV-=y7CxXVvL z{Ic%@k6#r3ki2`1|1I+GHU3@l{rKe^j<R3!cBkNcZIf44eB?)-JN@`2&!NYc{QB_^ z$&-FrFFfa>`0?*B&Ti7}exD$o8QKGdW4(stZzx><ZrM~g_`Bq9DIEIpoGkf}yxk># zRPmv+MLS?E{4v^Pg+qUh_O!yGGfq2HIQTEq_VXDKpJOfg9MEnm9QqQ6pU(~Q1|Gjk zTlz)+RpOf-U*@x=aKwL`_O`+iPe^-5;oytzuEN2ep}nVY@P9&kU*X`_XdfsX{4Lst z3I|`}GhAnxuk8PO{rfmaUHP7n{V*gh=Th`#|I7EH@MZopUOYFcGpBIGFL_x|IOf|V zzpHTY?-E~AIQT8%8wv-1pZINsgWn~-rEu^i@1yLOdC@e1hmX-ND;)acw5JsgeZfP8 zga2{bHHCv8(4JE`_@AULd6GCK4w;{<*Qd!Juoixm_J+ctAJE=ZIO37{Y$+W4Cunag z9Q=^>j>5s8puMYb@Mmc6DIEOI(%x4%_%+%G3J1ST`%vNF&(St&-NFAnasRw55FhvW zk~janbjkP6%M|fY=^&l~asRwLP24{(8^lLh%R1hnZs6h7GYKI1kp1v1d9t3OBY6px z4)P;B$+z%B>PuclU(Rh)>0rKh8K<fA*W37?6_tM6OX{Yy;>KERDmQV%Qn}IZn@X<( z1I)?Fv^5*8$aSMd)8466aHW!T!g9ANsi`hj6nJ!#q6VfHF4q<6ZdlThxMWGK^mgPp zsIFR$kyBh;xEmKc!=nqAO1;x=H<n}O@BgiEqleUE4Ri@<T+*Ozk9qcaYh%3srr`%3 zPfS^6v7fXJ>{);O1_>+P0C07|`2<DIk@U&<%iM>8%XpCuZ3o)E|2^+~_~XU?vTfiT zgaWYM=Z`h{KEU@Z-YSUyaq^zGb)Nr2`d=eYDj6^K*KH%u|Jb7mV@M+W<86eD7ysY2 zSf2kb6LOOOIXgbj|6Y!Nyv6YS<L`5x{{#A;vHiNpc)=EJBhUYBUcoPri238~hm4o` zzhbdG|5b?EQbVUIGG3sUZ6nYB+w|Y%I>JBRn#g$Z|6_~g`5*8V)aVKRUn}sxKnMFA z5C3@E;`@KS!2brn5Y}wJE;3%QpV>y<{6qe58IlP9c-JB0W&UqiEN}j9v)aCs{Qt^w z^86dVsu<dS6!^!H^!@+VVtM}8a9C^^y3h1O#tZV6ZRGhM(!cB<_{Wxz@iPCvS}f21 zG>O|>KTC5(#*6)D+sN}j##b^`o+J3j+awt;{{LyQJpTuL<=8yI|2qZ#!@zdfvZeMv z-a`5QAGZ2={%d?ydD8knWC!QXfBy;R{%HL$e=Ldb|2+N6_jEGKK2OvCw*_F0SW$G% zDJC8KET2mndpyUFTXWj}^Zg^u{@)&qJWO5;n!kx7fVOz1J5zb%w?32bKj#hbO!FV{ C?#c`R literal 12984 zcmeI2Uu+y#6~?c<ZDXR)nkFqK4Rlh4vMJ5tL<BiifJu`yTM_6gF_IfV_Qc*~S6X}5 zyOY#OC2*?>MZiNUMJOsl^#c!y)CVI~!WAHvKMzJi$U=aEgpd(DSmFiL6kMSQ&bjwH zp0jsnaE$U2sW)2BJ-_?ibIzQ(Gv2w**Nz^4rnjfZNb4~_Fo`A9n4u?<erUU)dCcrI z<{tAvJ2(3KM}yq&__LmU>%|{mzm+quzJ0Ri`c`8uN4?>JL%nAI&767Sovr5GbG_zO za(`txw~ZrSF=qCJJ96KB=I%3Zaer>Jd21()zq2)bH|jM9-adKg`mGm#eog12<FS99 zw{?ekkdLiivzd<%!QO`BPkPNX`+Q}4cyWS0f8O-^_Q06UY5r;cWzK<Wc7Wru{V4jj z9?GUM(~6_Ge6$r;C+T>~m>GuDF1Ulah~s$-oX5a<3`F1&cmzIuE{b_-liZ%D*J^NM z?NT)!uK@7)^U({GN4+uXCqtSJ#Qxx`0UsA=F1KmqF^xQ?B@Z{8;@?g)<MpYSeU_WB z<K`&)wE3vP$>^*VSS|*Uvlp6m9<W>tvQI~jM=f{iae1=Ax<<3yYMpDAxzEkc6EWG* z_;|v_u)64UwN||-dB&CIxfWHp8J~=!)5cV%;^F#p=WNZ{f%QwplS$)ovld6qv*q|y z;@^ifk{~NX9o8nBvRf*3l*^7g<^TS96F2co8M2SvAwHYoXQOd9W%$X;bE9$Z&G5fb zKUw*_$6bLpTF<QOa<}u1*5OXApSvaQCbwL=e%>j5tjn_lxePv=!8iIGyHnTkJwNV( zWYuA#*XwS7o@C{pwVt!|8|53Vb3Wrf+9=P8YmOa0{8W%X_JuD7!}WS?yb@KXf;07I z5Le2<p*@Xe{Y<q+z2<nO8kfgo`sx=PDD2y_Z*cE{!rpyBK59<xq2A!`-OLMn10LBs zxNm<(;=ufM>K^lt|D>sMsc%fi<mg{o%aJF)-ERR$>25jGebqi-Wm&x2|2ES1sJIg8 z5pbCy$KBw4HV&V=YeV2$V2ht;!27}Z1&iDB^x?R2{R4*7s`O!Aw3adAZyJ0Ad>BW5 ztzi8;Y|ew*%k*KsVl897h2uBDV<af~^Kj1G2UT)#_3Y-ak)%iI<ve(1&h#Y?&~tve z`E?raQF^>S*;zUJ8rtc~`Qg{o&h{pmJxbr{N2-|2aelga+xkg(F_}W=<yNCY#`)>y zzp;K2UXletJZEGzB%Yj~ZvI#6C*ge^eq=TIe!BU;te=E;)`#zc&gSyz<~fSrV-nu! z=iyE#WH~?G{C?{v;cYcDX9kqzy3S8G53HYr&v(>kdxoEGzTf&uc%{S7jtoED{Bzb% z!aM8pkuE=@q<@eqDoyT?32?dc!mHo`CJ3*C4}w>4{3>zr0b~!~$l%}2;BRE`pJnhr zWbnUb@LR;W4s%Fy1jjAC>G=<2@Q-Kkr!sgcgP$dCuM6eHO=|cuct5y2DP9NX^~g>5 zPc!_}hK1~j6voZ28MAA`R9nwZRpVr9WB5X&tTu+MS)MG@=E>Cfg_E>VWm@I9QKv1J z!}UqKp;Mk<zj0aF*gJBZCQP;J%_C79t<9w^8@pq3oaT{VmDmX)W^}YxKieAREg*F5 zE)n`_XG%!2N7F@4i3__yg<;;rLN}?2BFVO3DrBFHs2NSRc-wAmo2lM9V_MazGv>@> zG(+9BAzNZs23KxdFzh_mn|3%kD{D6DFO-`{s;#(LJ$){&)~6t<)v7JB4xO)8C!(qG zvc<HsbyDqR(gqcg!)v>H_97<P4AVXqE=tSwJLX!HWMj>)Y#{Qp5qBub$#Q(ObM35^ z<V2a)QP!Y8Z@4;HuG9V=m#uYpD&|FUynePAO-=CT<w3Xn%~rY(^mmI8{9%umz#sDX zF!&?HKaD;gzO49X6rWK1vx>`eko|;;*OdN{;tj>0R$QLr?B}rJm(cgmYhL*|s`Lwr z^LImOZFJbben($ayeMKiE-C)3;_|CR>MzeB`Q9LT3YX`Yuir*_aP#%@eDn3YGW5<1 zeP^KY&x=9FKJ=L<-zGXaf9t#qzk$*-?}wdNoY$MweMoWE55Nu;XZ@S7ONz5TfIXr( z>*e}Y6leWa<f+e#`AA0oW8i-Ne}rE@fB8NVVw~&7`P_i*=ih*TKmXrC@8>@Yy`R4U z4=|78@_EU+@$)|pouB_ehW~#0{m3n_KixX9{$cz6^YGK<ANo-F;rcuYy<eXII=?=H z(EIg~JQ|+=A?Rln=llm@Us9a&ISBn##aS=sGp9J~L+IxfXMG5JL2=d>p<h&-^+niA zinIPW^vjB~z65(kan_fhUsas-lAo*>S)YH0PS%U8AIV$Rh3IcWFV|W0ZE(3hqVGdK zQYX;|SXX_RCwv9^z~lX}^NREN3YY66eg>cmJ-xhPl@#at1h7XGXaDl-t0>NT$)lk- z>*bAUR&mx3!oH+9>m|>tinD$Q_MGCZmp7n!#aSQ1UQnF%@}{$>IO~hBmlS8cya6pM z&iWGU6~$Q}z+P3H^{cp!eIA!}5O};Fc3yGz|0CE^kM*u^8+yrC^a1z?j?CHrFJM;` zxAn=$U)Fu#>9g`*gzk3p{}uGNoBtB@e*SVF_IY_;!+8ZBpNE}Soa-as=luK^pbI_y z7;HcPHn?B^32;CE1?1VlxLhysJF7TfuQv3T6qkFK(N)D+zX<)D;(Wfc?<Vz-^>YJy zzn(HbP=45dKWx9Av*3O`2f#xd<$Pa(E$1!y1mJ!><@_tk59cF!G!*Cay$pL+an=vQ z7Jrh@6>z_vaz1ky7rp4_6=(k;>;=U+pE=lzinG25dr5KDe-HMu;;b*hUQwL&*I=(I z&U(qu;5tkGvi@)P_v0A+%5y@lR~uaJOYuJeF3&~L%lQ|*d}`2-D9-syUB(pW^KC%i zP@MHQz-JU^eGGm{an>(`Usjy;GvITIvtH`nhjBSCm?rReKkU5X>|g95#o7M=>`-ym z%YXMODbD%;_K4!Fe-d^@an?&*sh?c00(7&Ueh~I0#o52`tBSLKIiESjS-%hVyyC16 zVJ|4o`cJ}MRGjri*h`AD{!_4*6=!`3_KM=HmpoS$XZ;9lqpmya4}$ym%NY28rw_sX z`=tTy-!D&thsqD<GYjtDFGs-r`$eu(AI4>UUW4Dj<Ac2p<Q3=h<qtQhllYOkgm%=u zH?daYNxelM!oSp2*4q}$uP8r!zBiDkDYPz3(oPW_<EA@Sq}MFhqC#AriA`aGcN7b! zTP;&)*4beB-og->EV6`pFlk4zz#EEgkS)8Xn3&0ym(r;J5~h@E+l{A`)b1}PBHm(5 ztYr7C6RM5I4spUIgxznXGhEwlER5GDC(Bdva6>KspF=>Cxb%DtbPHj~`>c%hO9w~( zyCtuK5VjnKKInS#zD@rZ)5ekYG63P@;Qn7|YqB1olY@`>dB;Be`SSZgejmtui7)nE z>ab6FP6?O!N3o8D%Y4a$_u9Dc$6o-*%S0SyzTl8LY4t09$SDRP<ofY7lKE1<VPa|V zml1yk^W`A(#eR-DY4K+ezYQVB=eaUp;-4m#7Jr1DQd=+nS4fi<e+VyzZFWM9<MUr( z{rJ<w(&8^6ev!s?llj8<`$t;*Rm2~IkmK{SOXkb@f1Oxb{DFJj#1apxCi4ZoM4hzw zBYa~~Yhe9xeE#dM%$NAzA(j@uf*ZPTo%r9T`DyVNKTHGEmNB2>^S$rK|30y__>E08 zKyAJ2{|0H&;$P!{)Y|r^yZ*e_;m7CkwD>Ex8UKegKP`SGpaE)a`_skWMtwj2uZg9_ zAA?Zl!_C@!v42UOwD|d*P9f`u%fWjwe*C`>ON$@8&&{9bLDgiwpg&P3E&j}7PBDn* z2*>9&C-Y_f{hL@?{3ZOCiOM?h|4H-H;$QnH4N#j?>z{8)KR*B6AT9n7->lTuTYnGG z<h1z3yqn*42mAclL47~|<A^WMX~@ky;(tj1j+`queZ(oc0sQQLzw4B+jsr3e(8rI@ kml>CcdPy7O#Y*jl=Un2tQTP8P(&qQ=c8X7U6Fk%W7ws*9uK)l5 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/system.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/system.o index 407d40b2d5c67f9aaa162e963369f4be6155618f..881efa1a2c52053b339a81a64ab48bbb538d4ac8 100644 GIT binary patch literal 11728 zcmd6te{3AZ701Uv0Fwl8uxTR*V$%j{m*ncWrnOUA&Pn_u#Q_tW5=y|g-dpF6+}&Pw z_Yyma#1)E!s;G5nD)=K+QYkGCLaK#=${(RMEviyARS^nR`d8fwsriFSE<dWIBDn9( zzIXSszM(?>rxV@Ho6o%Y&fA&Uy`6EM=o{*<ud7p>>eMe(wZv4Z>GrCf)MiqxRLx2? zsvG7S#{P7h)$lfcK5bdH#r9W2S69IYVwi?*rhlu{;h(~14Sb+{c#A4;Z&2m8>O0HZ zq1<};z%Nf;ZcvBcU#>2-fPYZ04yWq<9#yaIg8Cz$_G5v5s=l-5{pHC^mk<1UCLZ7A z1FxL~&1v1|NZrW~ThyhSRI&&AX<4mq#2jK+hIuQMkJYO^3hc&J$^Ge@ll$Kv={<P@ z^7(6y-TYw-_Vb%cKU(|1uk<zP>x65qgO5_lOVLLixqRUD8Srbx@xpjG7QB9p2m4+F z*P-+$8iQ0lwpT|uNBfgLx2;xw-L-0zeM-<C=LF|rzTu`9nZq^u<<`g#+oW2mcJjum zZLO@@uxzw0`p;iqwdby@+Q(N^?eg-fomy74lN2B7Bpa)I4(zV0R2RmZg1Bkz(3t48 zrRQso#s_`ydN@ZL+y1RVy@-t4BZo147W0o67e9-+zJ`A->g#z0SiDd6`H51a@w!&% z;|Q$RV^??Tcu))0?I@0QWsLu=*ZC23F!@8&DqrpQSc{8YDeytPHPL+maj7G3QA{}Z zWxBRMh?rV|vH!~ke$v2?8~Aeu{(S>~+Q1JQcwpd<8@LS|$4-vT!@%%fiSC!$&x<*w z?!x+{zSnRq_&spVU3gEy{r7AD<BemE<IMLZmhs-?X9d)?V!xJBJ^b7N2G6l%PYU$e z#yarRY2@LN(Y|d;LB7%I9rsG16?&FmDp;W#gn^YUSiw{fy7`2Yz=w+Vi-`3|fA7|z zN0AbDyuw6w*Lcozc3)A+^+D+Q_AXb}X+6iw=Otu+<aQzL`qj#)|Ii-K=Cb=mh2{`( zHg7{G_u4sVIBEyA<4C(p0*rLMQXyUKt8!g=Hy&Oz4*TrT$)vqq_j!Ka&W(h&A70s- z$7P~72wXq>Z+=DB^@lvihD)=<tXB|XI=&G%H=*anD%v2JUb8HUBkFm=^Bp&>XNmgl z_g&Y@xOQ=)b$i+xpMoikW=koULcBa>`*}AFIZRD)j3Jiwq(cr};z}6S9V(?e>Gkv2 z78A9D1rn8=VyVix5LNwOeSgOgO{0OA4cw&jY5h|MeG@k6tAWj%H(G52_dRHhdS1@S z*l-8Kq*-CcwR+bVeQzS01Iu?Z+0b>ulJ8nQiO%(%9UFQQ8#=8vSP<*M>S%9Ap4ebv z&4!Lne0qFB!skh&`sZRTmxh{ebV@bAzgnpQl;SB`xBS$)vbI6N8(S=0r^`z@yfMO0 z96U8is*OUp1$do^hkJ^2md3M2`&W5+h3-&&oj8|SXAAM~kRS6A;!nmnsx>Hh8;zwX zo~3*z_|*x2e0k;6psr!Fl1DmA`9AQd6aIsh78uX9q7<2t&QkuQ)~WIi(Xv4;7bU5) zl>b2MRC!9YY*10}0;ywAxDl>^Qxh2{h~xZYVvaA<=x-r}#Qf)ABj>o8zd}3-IVN5K zXTV1PVNF$~-P=&+KB-D)e}`}MFB42t{vPDD{69AEWpJsr{P9Jg7QfZN+YP+O!21k* z*uZxfxMSdt8+ggUzXu%0bAiSY?*~jjGWZ`i@D~jHWdnZ=xSn^&F|CU-^*e+AUx2Sv z?=A9r;`|>5|3w2|QD1w0TMhgc18+C*E(5>Ezy}O`*uWn%@Vy59gn>VA;4c{X9}WD^ z2L4wAUoh~C2Hpg}Gqvu=Rs+A)!0$BhjRp>f6*c>P#K2tx&l~vD2L59Mf7!raH}KyZ z_}d2lj)7k?@J4um*P53b4E$~bPZ_vp-~n)aZp=cCDW$)addlGc9QilXD-FFasGkwH zh_50YdVx<kYVD+2o2DY}i0GBy3r3~_eB*~#cf_!VaCUDhO-#7H$_85t*)aa@UwQS9 zH^t`Ea%?Q;?b5PpY^-Sec0L%xT|lKk`wGVkCRC6uOsI*xJqhL>Kb%mLquIRcZ}wd~ zbRnKF>rmW7cB$ZGpdNavQLUpb1>?DFVRsbyR50Y(X>F(7@zO4BIeu7-46hJ)IhSqT zv+6SKQMJ9#^LM+xHtn>d^PHOw+&$VX=5;n++7BDih{X198qyHM9!f=xN6{?ibr$uY z%}7U^Q4_tZQ)2@|_iySQ8oR&0f2418Y_xaNP~Vtx?1HY|RtnuoHTgivEx7}3!S%Dw zh+9Z2-kItMpj*yI+)!m<ZXXO>M-MhkGK_^EY$^pR+v%j;z1kIb$cS(Uu0drhu1hsG z+LdM%W55l!yL(Dm-%a=N#vJyGymhbTH{|WxS_oYq7NJ{k-0gNc>uvMWt_pBxu3Nxf zT<37sfO9xpf-Si1E4S!p3$TR55kxeU(UF6;@fs?IK35<Y4oMelT$|=NB#}SHqAiF; z=RDeCf3LZ-bl<Oee4nqOzC@UxKDY%Py!rNw!9l=YmsZX8QbDs2;-k&@<gn+5Fv_^i zAB0{02%LzhXhjWqUQzAE+hvQJv!_%sXNPeA<~QpTn&He;kcDH0A$tlAe0pKT3k5sq z_1(=mFK{c)5R7?3AUq7E--hjET5anbrCaqOI~ztTH(He=Zr(0tJl`F)cf&mD=M4zM z5dt)eid&)U=oCU#-k)3Gz2^pgmO+jOoS2Z)BU6`m=<kTjT@k<kp+Ed2SN3};^1msj zpB7x|X9Sn}Il-m=LE<-q{^!WX>=4=U_@{|uJhI=T#BTw<mTb(9la2g#vN1a$_#J}J z2>u1ZUlP1c@L9pz1wSSD7X^P+@H+)RE%-XY=LBCb_#1*J1V1DAmjpj6c!%I0kj>-F z`|w5>FHE1Iac15`9LKXWa?#(-f`3`?Rf2a3ZV4`rN^n1f3FG-{Wa{q>aok^Z3tl9S z@!+96r%B?tt~N4+{1EZDKK=m#6Y6{|GW9p^doUrtJ2Lh63BmCUgVPLgjPn}|A%98u z-y`^}@J|YU%HaR1;GY-%rv>j7d`|F9g1;g7X2H)0zD4k}g7*pjrr`a8pA&pQ@Oi-p z1%F5It%6@5j^p`F!QUm0^N7!xCaPN?j?V|lFA~RjyjSRaB=`owoA4n83H^s6Q-9-r z5fk!lk*U8e!S54%o#6Ki-YxjB;9CTLKycg_V#0pm4~3PqQ*b;R<CGDce+#fK6#PMU zhP*8Jw*)^V_(OspCC=l|>;5?L_<Wrp&hx_lGeTd^%dF6Egns!P@Dy==E-`;q=zK-Q zIVU*(_F?rK#4*l?h5s4h|82p~3jaq0f79T9PVk+=|2%OXxAV|Hrg@<+*ZDiddED6l zg3y=a_O9TMM$-EG1Hm5?{3F4~1jqe1CR}eRZAD+r#5w*H#gF@PO!0YNMV#Yj|JB4% zU&e0<F4x;S;@s~u)Ncpzc)wl5xnK707W%T^yM;ckH%>{RBl)1vk<X1$;uw$3B9QMC z{&HQV1s@mwIl<+8O$vRvP7V_1@!{uwnK+LF^Y03MIS$VVF7Kmh!R7DcQNgeHeI(BD zbklsz5RcE-EOCyL{Z9#f8RzMkzD4?T2K_TJefB?V&_5T`ZzBEk2L1V%KKtYO3a0ov ze>bMT5V@%ZgZ{;sKKp-U(8qHcOg#SlUf4uDKK{+bdHmVGm3Tb<)iM3qs5@mD^xI<k z?7z;S-xbq;p7gs7`pK9+`)@Jm55@G$q(5xX-x1Si|D6W?bWA@(`Wb_MF{aP{p+Wy( zOn;E{%Le^tV*2cV$e{mxOuvKlkH&PEA2;Zn7CK~Vr8%J^`8g`!dXvw+dE&U9<-Xto zaa_-GU$7u_(iA&pE9l%0_XTplz~_XhPq&nA)k^;Oz9BiEAIAOH8vNH0M}G{B|9;sa z{3UPFy~E!Y!5`maFG7yV(%)6C==Zx#a2Y3$3F|bGe_Ws6FXQ?<4F0Q#$NjAu@!)mw zds;l64)RZe4<?LLj>B+-E8~zPf0YQP@^Cf=dFV%ZhAkhCa1wCN7pg?s4sDef4+53& zJuIO6hD5hYI8Hvo=nRLjpodOa(&w-VJcgC!=<Ed=!l{^B2q~`rHM2kfrxxc}rX&@* zX?<{AGaHoS-{En*l2qobc~xYcr$eFZp@{wPyi>KhgScEX*m9Ek#Wpg<%Xn6Sn(_8! zYX8&<*}B?4Q+#(qO?j4pb==<O`9=td<L5Y%z|fBOe}Vo~KMi#<aeHRChpW|ok{k!w zk@9$Ztgkix7wGUPMeT6>F(hu!<BxlZTK&(FBR^kBrqZ6vxL2#y|6p6>!R@hs{NDxf z{&xeb)&BxHrl4LXZqIB2j9UFqQvW>u*#C0)aC^S~DPY(?#|frR!x$_ix!1xn`eKrK zY>DXlS!zE+Io<}V;S=v4tK(}21$MOHw^FC@;zZ(p8Lb4PR{N&*$m2<Nq&(jKKScox AS^xk5 literal 11904 zcmd6tZ)_aJ6~M=K2qrN!Ax>*S+N|3^9ZC+{4J8htJty(Ma!HJRkfcC;>$`P)_1*1d zcQ4pUBwUoDNL7&oF7<~Xj6|gbp{i=B2vSQ7O)Dg*>Y~!3DwU!ZRgqe?X$ciU1oyq! z_wF9+8!DuJ=va62<~MKNynQn}yEEqpyAs{CH8qM;je1^HN=%iC-y~!$#??x-LM>Hl z>I(Qkn<>Ckzf|hj_u<nFA1EK&t|kZS)a2{6?UMsgZoGWx#gmuo)Umght4pgu->+52 zQng-(s#Ui_{q)EESYSU@+urf^^7y68hh9E0S2y&#wN~95{JDJSXD7ktl<sq|=Hxr8 z)TPxb-hutBTBEMT9DG=Yc_WpdtX2CJ$V-~y2Q$~j557IvdGcw<&t3WCb?>agetur= zN83JhT3?gCPPo<@_&~%ig&#G2`Or%zK(7&fLVws7yngft`)-EoQ2G<bAXSU))imcQ zf7EB~8s*horIM^ug7!EjI1cCPRzJfWuF;!p4E3;0YE?y!Ut5u_l@%F=S=&YZbJtYl zxvMMkY(qt!Twak=%PMl5{6jnOB^5pg^2RIFM)WrYe$(8cnCQ8s$7_z_gF1LUoTH3w z|5T@*LB{QoLrfpV{DXysPhqaF;ol4TdVT^d+9&HgrBpIn*9d(~!+d>mX}k6ZZNa=v zVyw$CeoxQyX>~aM7}}a#>UCHP3ma3QgZ7%k`vUw@)31|HIQEltZNCyeH3DP(9~t;b z1D`eU?-}?b2L3GrKWyN>fq%omZQvL?8JoSpD)(>o^<qw`TTv&j?=_qYUI$$BM!cus z{(IDicw@{l&U{~D8ShPAE1<3s`?Zwn;B^BStYh(x6xe5(>#E(qxPI|HTzWY1!bO;a zYFRi3zFWKc)zdFqe|-h!(u3eDt|M~&2p(>D0s5G(RtJ9RG`M##*|kF{$TwS^!)__C z0@w0N1uJm;z_+pm%b)NACm&14a1qmbA+hf5?(9q4kCb@YEsSLM4d>kS*oP{)-Va>Q z-si|VZ7=QS^AfT?a=Vamyh>%*e_#)1bJ>HULUZsqo428pJMA1aOxk{RKQhiD2SdAV zsgSAkRlcsg6Ll|)!vl7Z9?iJ>cDi2P&J6~(7ks!i$7Q6`_Z=_zZ+b<?@e*#@hD)=9 ztXmMqw10z6ZbXlZRkXoirg>TDN7(a->!qEH9wq9x+jAUi)Uk`3ts64d@B|ELI9f`< z5aQ)2+siu{$YE%TLkzL32OV<g5@$lc?ocV+NvD^`wwS0LOpvggE|w~s3t`p&)%Q0I z-YhZjNdq_8`MCNigMAY=*;hT=wr#drdUoDzC0#d{9<|{PhC#D}QOD}sQ1sl9Yz`zZ zJ(>-ibWrjft0UIFp}n=OBi7b#wZMef08;Dv^~hsw7S^=2w&QB`5ee6mCF-9G)l}-L zzVRtl2Y=O49ayTC>J+>QMp8JR7xSyN9<OqhMk_$91%Fzps)by*9(axLhg*jB7yHw! z^(%a`A?)K0;#_7s+lhaZ^q3D4e<;H5BYuQ<r6-IVycI`M=;va7NZYA!e2L~%r><nN zoQHN6^T$D>M(FpJTcAHziBc$rb{6xew4DlX6)o%3a#50Y7V{ryI~AT1E$dV``U0sJ zp>VC3hurV0z;RAQ(;oq#KI>&j;XLHk^e-AXc3Dk-nSrk|@U;ehi-F&6;N1qk)4=x{ zc*?-X415we#&ee9i1QoMw+;G_8~76je!{?i3|x;p<d|*_Gj-aa{|4}t>R$`>q{sQ6 z4f^jGcx|m=+zouCfv+|2n+*I`1HZ$-yA3>P;5h>?8Tcax{)B=5!oYuR;J-KUzZm%6 z4g3QGUk1;IYWMFd18+9)Rs-)f@VgBBUIR}X_#p#-%)n0=`11z-l7YW!;D0die;D|C z27U!R5UY(#yMf<h;EsW3f#bT7f*eyye=9X%(EkqU&yhYow$*Xs^TeCT&NIX>5FaIe z8p_qK>o*2YFY2+hT9;Al#;J%qA9}TS{lN(z-|XQP9Wm?`(qmgoBO{KdvVLD78${pn z%dhxBHa)g$Bw^$G|8Cmq3^=|M#BS?oYg19nXq^lX4dvW@x>q$cRJ1)i?+@W-pj@Es zMVKY*QXxI6#?inw&w>8HN$8v|M*CRuhjZD&Sm^JBpK$GrmNU+9X`hzTUQi4Lx8S=u zhh^T8>N4#>wfunVjX9nc?MzzdIVa;g`?Xli>uk7m5Vn~iiR{iaq`*RiRM<F)Vll6? zum>%McC;8a(R(&E)RWk?wKFlatGj!!D>;<x+?wbbQfa%Ot9O(FXIzcnRdPyBk5h2G zY<kcsWEAf^wFl5G=Yvk5vM{1|`%XHU&BF-$4#dLqx0ZaBZBJ*M16mdLzld;utwDLC ztxIqP(QS0OSy||Df&piLDeF0zF4l+LAaBg8=_T9;`U-*L!PIjKX=lLBWZfNZ#!)`* zyLAiLY3m$L5^xOrOR&MVJ>?X=Y#|r{hsy^HVJO1`1uf$>lm&fiKq~B#E>^iV%`qgQ zKKi01@I~hwZLxdTJiT~VuX%JAuc5v~7@sb<@zQw9?H__|{sD((%|NN3SpfdgR(rhP z^#X`8ZsL1k4?hU!9V(nr3D+&E19-b^cXIZGD(36}?%Mn|9iINt2|o*m2nl-vj&nL8 z;)R0kcY4mYoa;MfWpKtkAmARl(rv?LF{5_0C+S|?ZD)gU=7zI!(8=4yQP*>l_85$# zUS+^A91uXWu-FG(W9dL=v6utD@L;1alXH4qcPzZ;;Ubf;)NF&u2dZ!P_MV{uCkHpU z1~7?bioPGy@~M!sjQafEhFtCrd0j>hkNomJkk{PRk@q<`lhp~iw9o4}a%q2!(3kf4 zz4JQI{|xD1wuR)V|8e5ceiOv62RjzYnDvv4yjk$1;GY$IkKmsZoZrjQ&N{(ULjMNA zGlJhJI6u$O&gTWs3H=tqi-NBgJP`aQ!N&#vg5ZY*=a?gUnmEUq_vg<M|0MW{<IDUM zar8e%GG=omBfo`Y%w7?^Rq%Pi+XRPK3!TuPFACm7yaV!$f?LF~UwIVMLLBGSmxTTn z;!*qCiKCs{gnqx^n*_%nDKMcv{wTp|4{`K!GegMl6Z*Fco)Y>z=dn6t&>t0it+105 z9M4)f6$Sq?L&yWczasd!;BmnZ3*IUCq~KcxKO*=x!Qn>&oiJ|O1)mnYOYj-u7|(9O zj}ymn#C3+(wOQi4{xHXVFedD`ClvMfvx09B{FLCmf}at*Pw;uczbg1y!S59Oyx_cc zVf979cL;sGC_@?j-zj(lE~b!>?+Qiz-6S}#fmpFl@VkV5tKjg1XgO^W9M9x9C5UtU zIlleGqvM79W=uRTtiMOtm*bKW_Hq5;^T7;pUYD4U3Ont(r|_#NIIsCw6A(u~?-u&w zLjNAY4-5U>f=?Rsj|k4s6l`{sILGZx8t*A#U(R#*-BTxy8|%*q`!a6F1>YMs)!$DG z{x!j$75rYoPYKS?KCGT2&i?cIb%uC!++QKi{<HpT!oKu>UT`_z&JyQ-k5b&u5s&u! z7IE&E_0J3YvfsZ6`#9e?T@ZF8e^=O%>&6n;mt#VI?hi%%-9Q}gQ#r311^>FxUn962 zFFu!#UhmDM&+(a~_~7{pCXNI1jl#Z+!zRJyeH0g5J|7c;f9Uy0oc-BE{_G(h^*=?N z{bc=&urK}0MeJK-zi6;O9<k5*hYj|RMC{j-{i6o^QxW^D4?lwI6n*X-kJ!Hus;OCn zeLR1{#PMPMXASnBi`eJ)uu}&6a}oQjf5u?{wTS&6hVH3(gZ(!n_F4a|!Twtj`!i(! zyutp3h<(<-Xt4i&#Qr4N=gmxXe%8~?&+%vd2IA52Z6wa~f0XPu5s%upBKBE-ox%Ri z5&OMlztv!WQ^Y>&Z!y^Kjo5D``-zAh=KTgcIbnxHZK){iNPdJ07*DzGO%ca<%6-8M zag3+j7t9JfDe@h&pAyG?f!r_53HvlPbgMJO@qI(`d4v9M4f<z=K8pOi<~gA+`TG%l z?F@d=rW)rVspzVD;uyC~Sy`zj!R7NMF1RD~>q*9cO+=M<A;)CtZ}_c~xT5D@i{LUo z{48ModeV>D?<XF$zsI28WYD*WOMfsv{C*hqr<L^M!hh7~ap@Nv;}9o(74s+ZaGD2s z;Dz}pOCB6L#o%NzP_c|1*eW*c`zq$SSU~l**d`TAr}H63WjGB6d#HpZeIOje^I%yH zPm7=-oZ~rg5cI!E7MQ`IT^cbLr}7?}A6&hH1<LXN0x({2Ds$G`6iWTn;2J1mKRoVK zt!^YP=M1)-p?<NAOwlr)VW7=u`&nv#v_ZD6^v@K}9MGnG$H6*oZ}WH~gv9={A8}wP zNBgfQ#VM$hiQ6;7y<N5TGo;wdij+s&V|}&w&$NUMQq&IPe<gglJ;xv4^{e%Njucy| zJ!jmW%lHmkt^aqae{PTc<9{`9d+vV>ShfCF(7!;Wpk5|!&uj#QYW=s+AsNRX`(F+p zZqNNs0K@*-PY`t~QvY%<gcYcZN#>C$qU-0W{S@V&0Qzb8MEl3;=-fdA@PENNy@eMi X68Fn!B?#5ppIRSkJj9BWN8A4gAaX2Y diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/usb.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/usb.o index d05a00e9083557dc7b84e11f29d1120064296693..a2e88598bf5fc7579314498bb6175e996fcf3268 100644 GIT binary patch literal 6176 zcmeI0O>A355P-*aLkPcZ6KF+&yoMB|RbwSlkrEEbP8^3wfdt!;B0=Ri&zsna|71T$ ziGm<VMdC(+I3UCU!KJAXH^d2O#U%$06%uelYAX)qfD}|NJp?oJ-pupM+9nbw4xT7) zXTF`8-JRWMul)ApOw{l5frt;jhPovb;M1PE9<tRCJO+=VwiUY`NdDYw1b(9bqwK!U ztr!Mv1BCAP0c?0<DPFe^How_D2*A$0xNo-`<7%hiKE{7Y|BL?6SjY#LDt_4c>vPzt z^uf-ZK+m<?f$nQKj~~gW_Za-SSgR%O#lyP?o8Mp6^WUx2PRZP<{Y|rvT94kZ=ReBc zYZwo<&tgq+55_1K*Fd$hb()`{)%#8WE(FlW1lT#){LZe`V#K$z6!MMH`pN%b^M<`{ zw4p{1lrFykxb0gbUB>|YHN>4A@AyOTKxc=K8uDpNy8`VBv@6iAK)V9%3bZTmzplX4 z#Keonz|^brMxt2EnVD3!U@RBQhLur9c(7D1E@yM7mCa1nQl?ccD`PA;GB`3cJQf@t zF$PlQ{2*#W=g$)l4ja@nJT&sczpt9^%6P?;Yt<p=K+~HvKmh-mNdPnH(rE)4<*+=2 zrr(qQLGC`y{5adf&oMVNKFoZGxm@!j%omv_xP68BEw&~98_f4Lo?|Xk75`1!udxme zZ>+;x=<oB?M=J6zbIBXF^8&oje2#75WCoyvX}xjAZRC!B<8|2aZ{&`@%tp`O$Q^&$ z&BO8$nzD!9o-ffjfh&+qbjc_A7XMFTg=D=_!5@$}%kygs{(B4lH|M{OEs5ms#*LtH zZ#vlJ7nvW&mPGuc%nglSW<I3xHRd6Wf53c>xvcSH=8Mc9afXM_n3tGK{k~$p#rz`s z-#}Y(GP0XJ<WzqVS=UXQ*U!T!JN#mE84X~8`E8qf&YQSYD@#EW`qu%KbkbZ-#+6kq zxz=<cYq>^zHtOnA%9>bSiKvPRWmQque0<#Pi=?d7bm5RWTdk*wC_8I^8nP8zD^{(! zl)0)bKrL>iRum+sW@g93Gs)R#G(MR~Cc@)0lSwzDjEsXulJoIc(oR!OrL)Ccwy=tG zo52RmvQ@(6*!ucwRaI3nWvc9&ik6G{>39s>_=sA|n%IjA(P6w=DXBtQrS*=9VqrPE zf*<S+J(#DOZ^Rf-z^{VFj!3p*x_!70QuKtX*j2;zP)WygMRPS<SfMh+aZ1D>ukvPT z1I%JRpDNHyVo7rea39f$G+bhGHZhe<t2H_bm-sx;d-N3R)X4c6Lw?4?>GPC?{N?PC zZP5ee4Dx3j)qbwCPW)L9f0OkmwLDjtKcVqYJb8LOdF1`m=d*zEBzk^%FLnQP3;!$3 zb^rI6H_Vect@na6g+ovJsq1MEk=Ks6;o<V`6UX1FTsh4e@v|<i#}a?e!v{S6{T@E# z;paSDRLbK=L+0U~Cvm`j66qIzhXQ!VCI4I8;T@OwK65#5lE+{^$E|RQhhSwRZ>5&7 zwaQML5v{Cpsi39SEeNLRl?X0XDiAcyyxrQp#Dk~-JyNzCX+eCWQV8koQ3W~EJca+% z7#KyRs(&&&X+ll|UvM4Sbn7WLy?gYYg#>WBb;40H9RDzyq{=?YIeDIW{TsuH+vm8j zW4cd?7eL=f#Ps-4`w-xde&Wcj9#8i>8md*iJK+}bFSUy2D~p^P4%gEG-A|g;@9s$_ z;wlGH{b-M5{!%}>Z#J8MiN{~ycxfbF?3Yn#HvTsLm`vgwpJF9m#=ne=#&^#>>LhzS z{_BqEKFOEF+wxX99sC@i1*2qWawv39q0fJP{4Qkr-XVhR$LR_1hYaMH?zn8?U8Q;a OXpiHuERNi2>EIvt1HF;} literal 9368 zcmeI2Z){W76~K?5LlX*XLxF+XZF$ME4j6bLrP9Kx)%inGv~<a0BeAWM<Jd36!m*A0 zjDmuSC!q<c`#?5SbrMtQR%w9t0crol#8|fRu~Mh*Unf<oVSM1r{sK}X5oPDxcaC$o zwl`^?_90iwyZ8R?x#ymH&biOmhEoSdhn-Leq=ew7u-X#}u)TA&9W~7;JO&?vuGY!~ zcFzJtm%0E>EQS+*=y1comp{9|Jb&%dau^ow#zL1i<GiF3?OW-9r8fZf0aPaL#`-TU z&)>L6^X_kkrLqGH_rh@b)?Z)&$KQFQi)uL6(E|Uxjl2?qc(o(C<T~&pvZE7a?r)AR zksh)M_p(HKMd$arqJ7oymdoFL8Ww)}c;$(-1AV0L?<*_YXx{r+i|tg4y|g~rOtz36 zWE<H}_K{7rhf}PJY!kaKz^Yx^9<q<t6T4_H&20OdvT1q#`X#d4_;3R(-8J^WxoUXx zW!yW(;+*m02Gad2<Hv{hbN$jF`2%C%v{fcZ*Ii2wjnkOub8w#n01LFnz))x*tj5s4 z7<-HxulGDapN_fsk9<cy+lul(M4yqr0$btS<nTaWGz9xf=*N5LXR`Me#^@%lN4_RG z^6BKtN*vo~JKJfWQJGIMpZEp(o_vb-^l86VmG4OJdse^uBd30Q8aiKTX>WN&Yz^a@ z6z|j94_uWzEuqcHfsn~Xi9hWjJrFYabCdJpd9?F>>+4UF&2Fd`dz05>TQ$6Om$q+e zID~%Pa#{P7_DFl_Xdu5l|MS}U*@AM<v_(%;oaoZ2N8lLd<5h4Ve(F&;Rs|qmVJ>h! zpuXk#Uz>agp}#0*jm9KKGWUWL?OOzR*2K7$vw<Fojk~h)W66;U+JbT0C3!-6C^od` zKcnw;Zcse_Tfbn%3-y_JlP_s5^)VM}IY;M1pA82p-?Z~6iFp)q&%YCbYyWaWl?gh> zU1#8G68G8}f@g`zxXZcS)dpAPJcUtS_KR`fHHo>X_p9gAJE4&d+B^M`y|+*Y*-Uy< zc+Mu%&H|mu(xkI6HR+iAs%#A6MSF2hM!!WlD*mUlQQh|XlX3>hFX$gw!N2v63;24k z^sa9Ka8?ktuKSu3g-2S~g{VT2wX)`cH4m(LV9f(-9$53hng{;BJuosjxZm9|@`Xcg zJfF{|W|EnlJDo4O{*34L?<o}X)0r%`im925@1^{5(R2GEy?c6l_Vz{g_PRTg#o0aB z>e;!Icx10jBYS&#@rL`K3f-shnnhQtx)KH&tuJA~8(o7EMoo5UHK1P4qsSelAMgC8 ze3W?)_uu4tC-W-z&v5-2<^^72AM+9BSD4Q*k281iqD!S>o&aCPn(SF*eueog^8#;q zk@>u->;3RD@{sb6>^zXK_YdtOr2HoGuQG2l>j3m~eS!J7#qmc0qlbP(pdxx`AEf^^ zLs#`sHw^2Tu2zAa^*oTTzg7qG^*oRl>uvq@JdmfXc(`1}Zu`T?^xnqjCftE&qAwFv z-p9WuaK|onu!zV1itR>v9CTD8zO4zz?@<lqBTe}JCj9eF_)AUr4DwAnUc7O?iToMl z<cABK&*F#gFu!8)pES|)b`yRFIr(4oO8t)}@*!NWk)PX<lbt=RK=kZn9<}%&^KpxR znfau}k25bY7aLw?USYn`WDCI8nV)5Tk@>fg%UnjL`aa7?`N$mRLHsSKq5RL9@as+Z zZ;)?NUuWrkN9B)(OZEfEx==1nMN-f`M~!qMHJupo{K4rXLtZIWL$R^pT6-wzClBUU zyWYWE#;<ivr|6YD|4?k8MrqDic~vUr`Q-w1r=d6(^Yev*mxgpclRFYGCUd1}uL$|F zKb}k-^?b<Wq){@uaU|v^k9d$6866wwA5Dx6562F~6Y>6m(F2Lvin0T=VkmJaHjyxs z=e}6>%HD*R@-oN0;bMOFU~B@)+3a|}=zl5WWz!Shv2vz}<_rxEB@T=y;&aj(%;rm; zbjAu^PTJ!|uaGQy6LU~ZrZf3$CU+D)IEoddihcpNYT9T>Vk|zANPEXY+QZp$X(m25 zoSDuO3k)6dj%QM6Bf8Lrv2qC)PNR9jMn=4xSIneh$Ye9Yz`>H)=rC?g22%Oi*<>ya zUe5Q5iK%?v&*qb9bTx)u+ick}n9t?#_JB*)4@_r{;H{!=1Whl`*5jc}DOFR3i%QzW zy^=``bQ-0}KsKK`imAX`<XDlFv`vzLS#LH~H~}yA#_RonW=<qhQ-FDlQ>ev-k0)%# z_YK_{q{xZrL;f*=SU<;Yl9#!JqRc;R@k!=eE$%aa3c1T|s=mQ(+n)2x$(~MbQ?<x# zd)*t%Nq-l&sd~U|+kSj?nqu3zk-4qEow;p)H*?$m-OO$K>2r#Tt$$MK*Y=-Q{Nuq? z^E}&xzomG$lCL)5x0&1iq0cEQwtpTdJ)a0ff~ONyq(|TG=yQq+?N{?2C9m^pA9H)% z=a`fKpAJ--XH@Y|Dvtk-V~QQG0&_cFbId7TJCvT2N)O$orBsw2y{|LO?f9NmT+829 zdbA(zFt`2C!joxVyTur+w=2F!ahJIrm)*?mxQr`3I==BHdR}Ux=cJO?@0rug$<GmG z=XvIKd@m@j<9ki<Pb)pYV{Y&FT_xY6<lj?V>#s7m{Ua|yvQzuHje|$)>NsxXjvdE# z=61fh%t^oYe>Zd69=V^%y7E0{PRUbKc!jwwf4YhM515lZa)%=K-B5biRmQ7tDLtCs zQ}Q|=K2V&SM$ZH8*nVr_`=af)cILL<T;{glMwyEr%%b=hXKt^XR{HmgFxFYcKdX2} zarq2Y!}M=3(4l~Q{u1A%xZItI_bR@f+r&SmxU2Xxipx8V<o7BrXMwo<2B3zGo%AY_ z-vhLr#0xl&inh~m4!&NOc$I{)=yi!N(gTa+7}-Ne<i^b?ekW(nU3`g@PR#nrDXjfs zP|rxK=w*`;-<$IxlBNq&WU5qxNGdgJYBNeaf-Rs&(uh$jg14_ELb@&DO|iDv|K4zM zD!I!3#vesS<u%TipttHz=|6=HIucO<TvxXRjY?}!Z@`MykvK`7&}SxbeI~IB@AA6+ z)KNv|3!={&V)lHOH}oeF<l3H3IoD`?nO`%w$^6eXoBvoaLGp&D+v?1J>S*M@Nj`)Z zc_R6bwj}n8|6WAa$o|8;{$ZXkmCTp^3)pD1ew!Oe==Eu?%$N1)cQ#sI&O<N@&n2(_ z6#-n6EEQez5eo+R+5ULYxWjos-{<N5Y_Go_nH_tY`N0-?0^GEe%euiReHU*$|B4$( LOp74b_WXYX293A2 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/usbd_desc.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/usbd_desc.o index 301bba0cf6314fbddcadbdfccaff99df6f2b277c..b44bbbc8d8328cfd2e5118c29d27107399d6beec 100644 GIT binary patch delta 727 zcmbV|JxC)#6vt<FlG$W;R<ee$38y3x#h`@|<cu7r3xZ%L7J^t9?d<F<jg=M_k$<D2 zAZT%g2x4<(;4H2Y<lwH9yW+sg!YYl&%_MInru4z^-uu1pY4$b!dMT(#_9|h^3Yp8C zgPGa6+K+}<{gp3>pXM?4J|FkIj6;>Wsasi&hLCs=SzL(`RE6X=hGR$D30mP?>t4p$ z0{IdDM!ed^{}A8o;{S-(y7&jqn9l@@`a11+f=#pnacsqp@k!=!Aq&`$1Mp=IyRsj* zvM>~*W@(-4l5JGfY)W$l&knrKXbId7ux}+$b7DCf*s6}|xUTbX>I67(l$WK>hWfa3 zf?O{Vqe>moG+vy5r;u@{vF<LRZrS+i7Wf{nMFvmqfd89Tu2NM3MKxx9XINCz{24n| zfU=0;QmNucouVh|zj-T7aw}L?`L%KFnVuohNQLpX^@V^r&7kPS=%`RLGo`Fwr<4uU ovVx*W<I)?<)QP05b|k5lgTLNr@{Csej9kxT@{uObw=0$U4*|eq_W%F@ literal 3704 zcmd6qO>7%Q6vv;vp-P+Z(WIr3iqr)~C`Dvt8zB--8{0`*$t5OsN)VOYjlGUn@|V^d zNC*-UTsUw@C9d2!6vTl85<MV<ID^y!MI1N)Cyt<ANTmqg+kG!PnR<)h#8llk^PB(s znAx3O=k3MPQaY6aX({*u;*n5*?XkFThg}=SVGQ!=y;U6U1K0;o0qlHj)PA^N8h7OX zJMiFn@fE+r-LF1AG~fpDUyal!Xm8vdgM&#N57PF*FUBOX4}L~_cg#LG-2LXJ_)<>s zzwiY3<S)KYrl3kO9gIOSDaLi|t1<p*UX4%M|66@n6O0%qN64N!0ckY0+{=knG=6u) zeg)F0w80a3FR1&@o36Q#CpV~6uRNDCuX=v4<+RO0uT$>%f$4S4OBJ)zYq+5ZF9mek zX|_Gr%vl*6UoDhT-EDfCk%GpTyMgOBojN(KI&YYT)oK|-#W0fox9f7D@S-`h{L-3P z?e*IAmV-4md%hX8a4oZazt{BI*z@ZxFL3L@mhYPLR&F+z$<ABZoH^t8omuQ<E?y*V zWlfsNW^&IzxE$KH5%}Y;VJc(j$pJ9%->_z2B)vTx0=a9)XAOAhIKa_kAxYv%c~2z7 zxu28JfYJN(cphOwS??KE%%Y8II_^@y;c1LC#dv~k1uexfc`R}II3~R`*{MAQq_=ru zob88bhvlW01?kJIn`8T3g8nDg@3Zb2+k4D^=dr{&hqsF2XZV(h{skOU{jzhX*smP& zc%LN>Yz;OVwT3&WTXmS;hUo^ZRr1B!T4l9XbYJ)CZV~5vuOIY$s4bUP@(ZQf%F<G0 zv0AGx<V%aSNFQrs|B}<)yj-jVz7iq~9!(I9#TD20oc0hgqgZ*x>2BfarlaK#(J#9J zQm?xidzAfNW2;VBuY{Hvy*?5qkKQFi=A$*gj4v#&>A7KS%()uwCU5)ENt?v|kIq;$ zBll+>`6D7mJI#GvKf|2#>hoqN=!=S8o_Rv+iavfC0IoAXi}6+7QuJ#5ZRS*u8b4ru z9=V(;LLV{L*Y&BwDX*;UGv<2y&zVb|qQAvl&--OUoNt*^J(O3@!|eq9_sk`)=znCc z=cV&ZO|SpY2!rIk#A7_lVUzg6N15yUHqKm+e}=hUPcb1*N#V2)>s$}LFR1D9tIVZN z(XTVt^Il7c(`GLFAkSGpK_4)eyrSP`uIGI#Ax^X^0Q%`E?{H$HJVE?X5uugmi#UCI zq)l;$_*sEyO@*IU_>96IS9nI@=M)asV5bu}8)ySRvMuTPZriZ}cRK*9;RFs?8-oE@ z_>RK?$+OlR4oMUe?15G9bvkZWPN$ma-}OzD<C2fPBPfDR7i{m-q|#*n1f9nYeN$}# zY=7gI&OU#7Pa>yKa$jV>pJpC^p`!q|Iqx&k@aQW30-nVVG2Q>3R=4PNoW%)ZIT46W zN1a_6vz7c3XAwE|_56G6KbPPy*v8JV{oCdb{Y@6q{?V37e%ZejWRzc?JM4z-7UzFW z09&bBwJbfRoZ<!bd6LSZ^QGsfy7aYEp!fKv<g1d1AU17?zio#5oBVg;dgv8jbpO8r DYkHTc diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/usblink.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/usblink.o index 353f6f791d849714c88d09dff8c7ea5a6a78362b..35532c2951ec759fea05da68906b2a3c2f5d65c7 100644 GIT binary patch literal 2976 zcmbVOO>7%g5FUF=C{2V)(jQO}T||T&iEQksh#FOBoyJKcOoL+gfIv7K`$e|uzwEA| zZICdWIB<xo91)5ThX!%z0SOLJ5OCng1=JfzTseTEN<^v^X1p`@@?s;zSi3Xxy>EWr z_<7fFr!x!DNCZS8@HzB7K>>D-_HDas+As#AXtl<_G4em3HI1L>LVqRfcQ(J;?HJJB z%SLwh4EW^U1ndLY$+P!iqZEalGh!!C0Bp6Q(0(Th$!63}etiQrrVPko@-5^dAGUF= zy)y!jkPVN+_+B=(dvC(t?`(c|i|S#|$c3#Z0othB?~b)rh&wEQtaFh2=n4BK9D%lT ztQ)gUwSPM}I4yf2-Pybo^gjyw6PVw_K31ctWDDR~%5UO+SEG^S-YE6*ZMT<jJaT9c zNtsFDLz{fG!LnvbPG!b(3o}h`tx~RCwF-ncreE;NH<Wq7%)XM%EM0yv|5EM>E&Nwm zym;|>Gq!m7ikYj|D}|C%u9@p~*Yr!uOief3`g*y7mRl&5eO2(At}>I>?DT9rk+c%C zX3TM`(`dz~rU<tZCaommv$X4f5js0Z;Ln3W6l37Y0x<A1NDR!R3!OL^kmq4Uqaj?5 z>r;#$r!W-3$u{5tQvZ;1UGFgd9O9JUWcFvQ1ODMYmvB82>fdHQ9cseGr+JAOFd}A8 z2l)@<uOcH7;>UUsw6E|kg9U|3W)Pyn<`De7A^6Q9_=iLA-68mG#K&<5zoI4y_6hJM z+JpN19&zHEJg_keLirId!s8ka{a@4MHE~u{L6zT7FFS>+$`>%J{B+G(t0<T(_OV)# zS)QsD=bG#5%7wDGR4e!5mK%^?%q-8PGWq3&g={*P&!y%v={$I9BTql%`TCnRsHh_P zE6p0E&SI{4$9KT-JmvZePPqbARV_5GOJOM>n)2k7*DJcH{0u?>^WEJ8OyIu5r|%Nu zCpA37_$dv4EtF@RZBnajCy|fOy`B`=I)nI$9tu!mTd&&)@lS^MbiPQa|D%D~y}!@4 z;E%Gu#hUVm`P&*U{0|tXK2Nbt>SMO`x!q!1@BdTA^|}4PIORXhHmTp)*7N_txSsz$ z<CNzywn@o3mpnGFO(Ks(`mwtn^v*x==~*apj`>tKjLSN``lIL^XFz5vxXHMz3(hdU zz`W~K-&sTLyMZo=<*JHf`RbYvR*_D<wdQ$Xxpi`gp0LiNOQbG>mQ|@2oC;WldbO%* zey_;?H%ttr5$I1)8!?g#JfFbp&q4e%XwdJ=7J&5^{EDz?cqk9yMX6+dat@znTz|v8 zrPW1RS9JIpL@B2p-(q4a2<zRYz5od{h&n3(Yl*isT;ipVG_I4a*T2n#*pPUEZ8QeW z@2>{~#w8}w{OCK9`Z7QI&qJl+c!lLI*QfVjSQzfc5KcaSMPVA8XK;u0F<hnRpI)E( h()Uh@?$V}EehF0XF7*YVKdgh|Z7%e>5LxT-e*+v`B@6%n literal 4944 zcmeHKUu+a*5TCn6tbkf5APUkgsis7_w2d0hG-lh<7UGp+@0$2G*X`YwUbuhk?rBR+ ztbH&%_|Q`ljZcISLwQ9b5B`h3`at{_9;@=M26-UiQfGE&;OpM4FUB{9v@`RY`F=Cs z?DqSXw}+D>@mLH*V(>ZK^#lcIZM|!ozG=dPum!%+GQYIz+RyR>usES&^@XoikZ-xJ zLG4B=wsJ#*ON(0;C!PlL7Sf!Jzh!>#tJZdDRoi}v{Pqp-7q*i|dl@)~IB%o|R_Y7i zUL<bxx2e9=CS70naz(9mvkkD0nP|Tar_RJ7ZEZ9Y+mU-Q4z-vLiE7+Te0>^D9o5#? zd<Wy_Hp12p9ct7U>;b>#%{KE^ec?O5584;?*#Uk|Z3*{9xluJ*>TBuqd(HQu6Kd9` zfS2n3wzl?&>_P3Hdf$Qkm$8?reFKTrI6OoA)c;w;e#e<DEyZiG4OllG)TVh#U+*q$ zs-2I+E$Po5jMZ{DOAQu(h(8+S>*!DIizR5D>fWRu+8@nNo@wAiEqD$9hH-G#Djam3 z?7^x#UC5VC8d=PNO84__{<N+4>#3Jh$)m?!$c&{Y5uZ#Al1C}`<lY4CP2m5Y!06D> zb9&e4u}M8$E*G-1R=%XqlpWohwe^ASic_A+7tnIDvw6?XdR52P6GmTmUr%qs=<U<H zET`CwR?q(Zgd4p&MS6Ss=p_0V!7~W(C|_%qqBXr?05ts9Of+N)%Vr;-D(mGTbmI!Y ztbB~|R!(nW{S@Om`#IL6G`LUk0@L(WBR+&U)uju8<Vv8x^tE)sASyZwW6HjypIOGm zH_<0?@rUw{_#WAToM!wu`{qVAP-&nz68Ci@{vqNqCI1}fUuIl<+@vo*3eNtWIN}=I z@8_t$Oy6n5|3EyZ<aa5HG<ZPq0+T)(<Qb~LdIY{12h}XUBLY7Vfj=984@KbP5%?<+ zxP|yOoWya|BxeEz#fbcB1b!w0{}^%NUqwx_B~b7Q<9~*5xO<y-&WV$@+>>IbY;U+^ zO&4qdChV-8f5Sd*Wl!23bmjz4*`*wVS;wmc=3%>lxz0Se7#*z6%-9a(-J_+v2W2-k z?`F6>RZMwE$vHu=k!S2gkry_`QeN4yPS}maM9#ciZoC3xeQB6`v1(Us-VkI)ljDN} z$;|l3NNPBpNe>JrhcnptsSJJYOje*^=g^y|mhOOu%Wsxw|FrkRmS=(Gy0+tuSos1J z?P9hvFVpe2jG4X;>JB-!<=MDvFQ0`uYH}SSld)Y-NJechiLKBh?d0d$hR;(ybq+DU zH-z^yz8i5mBSn&I5WZVL)Gx73{CgDqHMSFoKd#_YY!lC31^<-oaG!E+?!bJt|L>K2 zweD5MscyT%{}bEcy4M&F^Iuo;b+$>}W}Et4cN(EjBKWSrg$;}oznb3?!X>|zaq6>! zIY{kdJUpL0jEDR0XPkKUDLhjVJh=#-iozrB647}I&sK$hPT^7U_Y|Hdl>D;_56!2C zV;?CvUnzd%9OL2l_5$NFXW_Z1;404-jMIFcRQi$gQ06T6>vhiGiJIO+!R4H!{GAHV z-<(hVsJNuy|7rcJQ|_V`4hX)?zQhIBg}`v<i=H(NhU+<jo)ycn3zp&8a~>EuI&6$- z*9F5VlSApf#vw4W*<t`wvLC@^MxmUw3K%RGi+0JATK_>)zch;Q7lw%#$!(rf;5FXO zbk@+kO-W#VHTd9zW&T9mgg8;j9Odtco-N_wFUfxOWx%*ds2w<f0pbj=H+lVXXk$`e z_<GSG&OQNH%lbnhT-Hk;CdQlfKgadWP-C)QXvZSfU*S*IE=gn^UVjAfX7itVI9Nb& z5}H4K&B=P1|LcfR|MK^UrZ1~p|5X84%f40J>`}>g?KR#%y$*C=h3nIq5*m?TX%{t& c@|hG0T)$T~eMM(jv-KBw|1)Yb+95jl2Pc-%VgLXD diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/utils/src/lighthouse/pulse_processor_v2.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/utils/src/lighthouse/pulse_processor_v2.c index a1e8fe960..9db6d86e8 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/utils/src/lighthouse/pulse_processor_v2.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/utils/src/lighthouse/pulse_processor_v2.c @@ -46,99 +46,99 @@ static const uint32_t NO_OFFSET = 0; // The cycle times come from the base stations and are expressed in a 48 MHz clock, we use 24 MHz clock hence the "/ 2". static const uint32_t CYCLE_PERIODS[V2_N_CHANNELS] = { - 959000 / 2, 957000 / 2, 953000 / 2, 949000 / 2, - 947000 / 2, 943000 / 2, 941000 / 2, 939000 / 2, - 937000 / 2, 929000 / 2, 919000 / 2, 911000 / 2, - 907000 / 2, 901000 / 2, 893000 / 2, 887000 / 2 + // 959000 / 2, 957000 / 2, 953000 / 2, 949000 / 2, + // 947000 / 2, 943000 / 2, 941000 / 2, 939000 / 2, + // 937000 / 2, 929000 / 2, 919000 / 2, 911000 / 2, + // 907000 / 2, 901000 / 2, 893000 / 2, 887000 / 2 }; static inline uint32_t cyclePeriodToMicroseconds(uint32_t cyclePeriod) { - return cyclePeriod / 24; + // return cyclePeriod / 24; } // Reset angles after fixed period to avoid using stale data static void clearStaleAnglesAfterTimeout(pulseProcessorResult_t *angles) { - uint64_t timestamp = usecTimestamp(); - for (int bs = 0; bs < PULSE_PROCESSOR_N_BASE_STATIONS; ++bs) { - uint64_t elapsed_us = timestamp - angles->lastUsecTimestamp[bs]; - if (elapsed_us > cyclePeriodToMicroseconds(CYCLE_PERIODS[bs])) { - pulseProcessorClear(angles, bs); - } - } + // uint64_t timestamp = usecTimestamp(); + // for (int bs = 0; bs < PULSE_PROCESSOR_N_BASE_STATIONS; ++bs) { + // uint64_t elapsed_us = timestamp - angles->lastUsecTimestamp[bs]; + // if (elapsed_us > cyclePeriodToMicroseconds(CYCLE_PERIODS[bs])) { + // pulseProcessorClear(angles, bs); + // } + // } } TESTABLE_STATIC bool processWorkspaceBlock(const pulseProcessorFrame_t slots[], pulseProcessorV2SweepBlock_t* block) { - // Check we have data for all sensors - uint8_t sensorMask = 0; - for (int i = 0; i < PULSE_PROCESSOR_N_SENSORS; i++) { - const pulseProcessorFrame_t* frame = &slots[i]; - sensorMask |= (1 << frame->sensor); - } - - if (sensorMask != 0xf) { - // All sensors not present - discard - return false; - } - - // Channel - should all be the same or not set - block->channel = NO_CHANNEL; - for (int i = 0; i < PULSE_PROCESSOR_N_SENSORS; i++) { - const pulseProcessorFrame_t* frame = &slots[i]; - - if (frame->channelFound) { - if (block->channel == NO_CHANNEL) { - block->channel = frame->channel; - } - - if (block->channel != frame->channel) { - // Multiple channels in the block - discard - return false; - } - } - } - - if (block->channel == NO_CHANNEL) { - // Channel is missing - discard - return false; - } - - // Offset - should be offset on one and only one sensor - int indexWithOffset = NO_SENSOR; - for (int i = 0; i < PULSE_PROCESSOR_N_SENSORS; i++) { - const pulseProcessorFrame_t* frame = &slots[i]; - - if (frame->offset != NO_OFFSET) { - if (indexWithOffset == NO_SENSOR) { - indexWithOffset = i; - } else { - // Duplicate offsets - discard - return false; - } - } - } - - if (indexWithOffset == NO_SENSOR) { - // No offset found - discard - return false; - } - - // Calculate offsets for all sensors - const pulseProcessorFrame_t* baseSensor = &slots[indexWithOffset]; - for (int i = 0; i < PULSE_PROCESSOR_N_SENSORS; i++) { - const pulseProcessorFrame_t* frame = &slots[i]; - uint8_t sensor = frame->sensor; - - if (i == indexWithOffset) { - block->offset[sensor] = frame->offset; - } else { - uint32_t timestamp_delta = TS_DIFF(baseSensor->timestamp, frame->timestamp); - block->offset[sensor] = TS_DIFF(baseSensor->offset, timestamp_delta); - } - } - - block->timestamp0 = TS_DIFF(baseSensor->timestamp, baseSensor->offset); - - return true; + // // Check we have data for all sensors + // uint8_t sensorMask = 0; + // for (int i = 0; i < PULSE_PROCESSOR_N_SENSORS; i++) { + // const pulseProcessorFrame_t* frame = &slots[i]; + // sensorMask |= (1 << frame->sensor); + // } + + // if (sensorMask != 0xf) { + // // All sensors not present - discard + // return false; + // } + + // // Channel - should all be the same or not set + // block->channel = NO_CHANNEL; + // for (int i = 0; i < PULSE_PROCESSOR_N_SENSORS; i++) { + // const pulseProcessorFrame_t* frame = &slots[i]; + + // if (frame->channelFound) { + // if (block->channel == NO_CHANNEL) { + // block->channel = frame->channel; + // } + + // if (block->channel != frame->channel) { + // // Multiple channels in the block - discard + // return false; + // } + // } + // } + + // if (block->channel == NO_CHANNEL) { + // // Channel is missing - discard + // return false; + // } + + // // Offset - should be offset on one and only one sensor + // int indexWithOffset = NO_SENSOR; + // for (int i = 0; i < PULSE_PROCESSOR_N_SENSORS; i++) { + // const pulseProcessorFrame_t* frame = &slots[i]; + + // if (frame->offset != NO_OFFSET) { + // if (indexWithOffset == NO_SENSOR) { + // indexWithOffset = i; + // } else { + // // Duplicate offsets - discard + // return false; + // } + // } + // } + + // if (indexWithOffset == NO_SENSOR) { + // // No offset found - discard + // return false; + // } + + // // Calculate offsets for all sensors + // const pulseProcessorFrame_t* baseSensor = &slots[indexWithOffset]; + // for (int i = 0; i < PULSE_PROCESSOR_N_SENSORS; i++) { + // const pulseProcessorFrame_t* frame = &slots[i]; + // uint8_t sensor = frame->sensor; + + // if (i == indexWithOffset) { + // block->offset[sensor] = frame->offset; + // } else { + // uint32_t timestamp_delta = TS_DIFF(baseSensor->timestamp, frame->timestamp); + // block->offset[sensor] = TS_DIFF(baseSensor->offset, timestamp_delta); + // } + // } + + // block->timestamp0 = TS_DIFF(baseSensor->timestamp, baseSensor->offset); + + // return true; } /** @@ -149,86 +149,86 @@ TESTABLE_STATIC bool processWorkspaceBlock(const pulseProcessorFrame_t slots[], * @param pulseWorkspace */ TESTABLE_STATIC void augmentFramesInWorkspace(pulseProcessorV2PulseWorkspace_t* pulseWorkspace) { - const int slotsUsed = pulseWorkspace->slotsUsed; - - for (int i = 0; i < slotsUsed - 1; i++) { - pulseProcessorFrame_t* previousFrame = &pulseWorkspace->slots[i]; - const pulseProcessorFrame_t* frame = &pulseWorkspace->slots[i + 1]; - if (! previousFrame->channelFound) { - if (frame->channelFound) { - previousFrame->channel = frame->channel; - previousFrame->channelFound = frame->channelFound; - i++; - } - } - } + // const int slotsUsed = pulseWorkspace->slotsUsed; + + // for (int i = 0; i < slotsUsed - 1; i++) { + // pulseProcessorFrame_t* previousFrame = &pulseWorkspace->slots[i]; + // const pulseProcessorFrame_t* frame = &pulseWorkspace->slots[i + 1]; + // if (! previousFrame->channelFound) { + // if (frame->channelFound) { + // previousFrame->channel = frame->channel; + // previousFrame->channelFound = frame->channelFound; + // i++; + // } + // } + // } } static int processWorkspace(pulseProcessorV2PulseWorkspace_t* pulseWorkspace, pulseProcessorV2BlockWorkspace_t* blockWorkspace) { - augmentFramesInWorkspace(pulseWorkspace); - - // Handle missing channels - // Sometimes the FPGA failes to decode the bitstream for a sensor, but we - // can assume the timestamp is correct anyway. To know which channel it - // has, we add the limitation that we only accept blocks where all sensors are present. - // Further more we only accept workspaces with full and consecutive blocks. - - const int slotsUsed = pulseWorkspace->slotsUsed; - // We must have at least one block - if (slotsUsed < PULSE_PROCESSOR_N_SENSORS) { - return 0; - } - - // The number of slots used must be a multiple of the block size - if ((slotsUsed % PULSE_PROCESSOR_N_SENSORS) != 0) { - return 0; - } - - // Process one block at a time in the workspace - int blocksInWorkspace = slotsUsed / PULSE_PROCESSOR_N_SENSORS; - for (int blockIndex = 0; blockIndex < blocksInWorkspace; blockIndex++) { - int blockBaseIndex = blockIndex * PULSE_PROCESSOR_N_SENSORS; - if (! processWorkspaceBlock(&pulseWorkspace->slots[blockBaseIndex], &blockWorkspace->blocks[blockIndex])) { - // If one block is bad, reject the full workspace - return 0; - } - } - - return blocksInWorkspace; + // augmentFramesInWorkspace(pulseWorkspace); + + // // Handle missing channels + // // Sometimes the FPGA failes to decode the bitstream for a sensor, but we + // // can assume the timestamp is correct anyway. To know which channel it + // // has, we add the limitation that we only accept blocks where all sensors are present. + // // Further more we only accept workspaces with full and consecutive blocks. + + // const int slotsUsed = pulseWorkspace->slotsUsed; + // // We must have at least one block + // if (slotsUsed < PULSE_PROCESSOR_N_SENSORS) { + // return 0; + // } + + // // The number of slots used must be a multiple of the block size + // if ((slotsUsed % PULSE_PROCESSOR_N_SENSORS) != 0) { + // return 0; + // } + + // // Process one block at a time in the workspace + // int blocksInWorkspace = slotsUsed / PULSE_PROCESSOR_N_SENSORS; + // for (int blockIndex = 0; blockIndex < blocksInWorkspace; blockIndex++) { + // int blockBaseIndex = blockIndex * PULSE_PROCESSOR_N_SENSORS; + // if (! processWorkspaceBlock(&pulseWorkspace->slots[blockBaseIndex], &blockWorkspace->blocks[blockIndex])) { + // // If one block is bad, reject the full workspace + // return 0; + // } + // } + + // return blocksInWorkspace; } TESTABLE_STATIC bool storePulse(const pulseProcessorFrame_t* frameData, pulseProcessorV2PulseWorkspace_t* pulseWorkspace) { - bool result = false; - if (pulseWorkspace->slotsUsed < PULSE_PROCESSOR_N_WORKSPACE) { - memcpy(&pulseWorkspace->slots[pulseWorkspace->slotsUsed], frameData, sizeof(pulseProcessorFrame_t)); - pulseWorkspace->slotsUsed += 1; - result = true; - } - - return result; + // bool result = false; + // if (pulseWorkspace->slotsUsed < PULSE_PROCESSOR_N_WORKSPACE) { + // memcpy(&pulseWorkspace->slots[pulseWorkspace->slotsUsed], frameData, sizeof(pulseProcessorFrame_t)); + // pulseWorkspace->slotsUsed += 1; + // result = true; + // } + + // return result; } TESTABLE_STATIC void clearWorkspace(pulseProcessorV2PulseWorkspace_t* pulseWorkspace) { - pulseWorkspace->slotsUsed = 0; + // pulseWorkspace->slotsUsed = 0; } static bool processFrame(const pulseProcessorFrame_t* frameData, pulseProcessorV2PulseWorkspace_t* pulseWorkspace, pulseProcessorV2BlockWorkspace_t* blockWorkspace) { - int nrOfBlocks = 0; + // int nrOfBlocks = 0; - // Sensor timestamps may arrive in the wrong order, we need an abs() when checking the diff - const bool isFirstFrameInNewWorkspace = TS_ABS_DIFF_LARGER_THAN(frameData->timestamp, pulseWorkspace->latestTimestamp, MAX_TICKS_SENSOR_TO_SENSOR); - if (isFirstFrameInNewWorkspace) { - nrOfBlocks = processWorkspace(pulseWorkspace, blockWorkspace); - clearWorkspace(pulseWorkspace); - } + // // Sensor timestamps may arrive in the wrong order, we need an abs() when checking the diff + // const bool isFirstFrameInNewWorkspace = TS_ABS_DIFF_LARGER_THAN(frameData->timestamp, pulseWorkspace->latestTimestamp, MAX_TICKS_SENSOR_TO_SENSOR); + // if (isFirstFrameInNewWorkspace) { + // nrOfBlocks = processWorkspace(pulseWorkspace, blockWorkspace); + // clearWorkspace(pulseWorkspace); + // } - pulseWorkspace->latestTimestamp = frameData->timestamp; + // pulseWorkspace->latestTimestamp = frameData->timestamp; - if (! storePulse(frameData, pulseWorkspace)) { - clearWorkspace(pulseWorkspace); - } + // if (! storePulse(frameData, pulseWorkspace)) { + // clearWorkspace(pulseWorkspace); + // } - return nrOfBlocks; + // return nrOfBlocks; } void pulseProcessorV2ConvertToV1Angles(const float v2Angle1, const float v2Angle2, float* v1Angles) { @@ -240,87 +240,87 @@ void pulseProcessorV2ConvertToV1Angles(const float v2Angle1, const float v2Angle } static void calculateAngles(const pulseProcessorV2SweepBlock_t* latestBlock, const pulseProcessorV2SweepBlock_t* previousBlock, pulseProcessorResult_t* angles) { - const uint8_t channel = latestBlock->channel; - - for (int i = 0; i < PULSE_PROCESSOR_N_SENSORS; i++) { - uint32_t firstOffset = previousBlock->offset[i]; - uint32_t secondOffset = latestBlock->offset[i]; - uint32_t period = CYCLE_PERIODS[channel]; - - float firstBeam = (firstOffset * 2 * M_PI_F / period) - M_PI_F + M_PI_F / 3.0f; - float secondBeam = (secondOffset * 2 * M_PI_F / period) - M_PI_F - M_PI_F / 3.0f; - - pulseProcessorBaseStationMeasuremnt_t* measurement = &angles->sensorMeasurementsLh2[i].baseStatonMeasurements[channel]; - measurement->angles[0] = firstBeam; - measurement->angles[1] = secondBeam; - measurement->validCount = 2; - } - angles->lastUsecTimestamp[channel] = usecTimestamp(); + // const uint8_t channel = latestBlock->channel; + + // for (int i = 0; i < PULSE_PROCESSOR_N_SENSORS; i++) { + // uint32_t firstOffset = previousBlock->offset[i]; + // uint32_t secondOffset = latestBlock->offset[i]; + // uint32_t period = CYCLE_PERIODS[channel]; + + // float firstBeam = (firstOffset * 2 * M_PI_F / period) - M_PI_F + M_PI_F / 3.0f; + // float secondBeam = (secondOffset * 2 * M_PI_F / period) - M_PI_F - M_PI_F / 3.0f; + + // pulseProcessorBaseStationMeasuremnt_t* measurement = &angles->sensorMeasurementsLh2[i].baseStatonMeasurements[channel]; + // measurement->angles[0] = firstBeam; + // measurement->angles[1] = secondBeam; + // measurement->validCount = 2; + // } + // angles->lastUsecTimestamp[channel] = usecTimestamp(); } TESTABLE_STATIC bool isBlockPairGood(const pulseProcessorV2SweepBlock_t* latest, const pulseProcessorV2SweepBlock_t* storage) { - if (latest->channel != storage->channel) { - return false; - } + // if (latest->channel != storage->channel) { + // return false; + // } - if (TS_ABS_DIFF_LARGER_THAN(latest->timestamp0, storage->timestamp0, MAX_TICKS_BETWEEN_SWEEP_STARTS_TWO_BLOCKS)) { - return false; - } + // if (TS_ABS_DIFF_LARGER_THAN(latest->timestamp0, storage->timestamp0, MAX_TICKS_BETWEEN_SWEEP_STARTS_TWO_BLOCKS)) { + // return false; + // } - return true; + // return true; } TESTABLE_STATIC bool handleCalibrationData(pulseProcessor_t *state, const pulseProcessorFrame_t* frameData) { - bool isFullMessage = false; + // bool isFullMessage = false; - if (frameData->channelFound && frameData->channel < PULSE_PROCESSOR_N_BASE_STATIONS) { - const uint8_t channel = frameData->channel; - if (frameData->offset != NO_OFFSET) { - const uint32_t prevTimestamp0 = state->v2.ootxTimestamps[channel]; - const uint32_t timestamp0 = TS_DIFF(frameData->timestamp, frameData->offset); + // if (frameData->channelFound && frameData->channel < PULSE_PROCESSOR_N_BASE_STATIONS) { + // const uint8_t channel = frameData->channel; + // if (frameData->offset != NO_OFFSET) { + // const uint32_t prevTimestamp0 = state->v2.ootxTimestamps[channel]; + // const uint32_t timestamp0 = TS_DIFF(frameData->timestamp, frameData->offset); - if (TS_ABS_DIFF_LARGER_THAN(timestamp0, prevTimestamp0, MIN_TICKS_BETWEEN_SLOW_BITS)) { - isFullMessage = ootxDecoderProcessBit(&state->ootxDecoder[channel], frameData->slowbit); - } + // if (TS_ABS_DIFF_LARGER_THAN(timestamp0, prevTimestamp0, MIN_TICKS_BETWEEN_SLOW_BITS)) { + // isFullMessage = ootxDecoderProcessBit(&state->ootxDecoder[channel], frameData->slowbit); + // } - state->v2.ootxTimestamps[channel] = timestamp0; - } - } + // state->v2.ootxTimestamps[channel] = timestamp0; + // } + // } - return isFullMessage; + // return isFullMessage; } bool handleAngles(pulseProcessor_t *state, const pulseProcessorFrame_t* frameData, pulseProcessorResult_t* angles, int *baseStation, int *axis) { - bool anglesMeasured = false; - - clearStaleAnglesAfterTimeout(angles); - - int nrOfBlocks = processFrame(frameData, &state->v2.pulseWorkspace, &state->v2.blockWorkspace); - for (int i = 0; i < nrOfBlocks; i++) { - const pulseProcessorV2SweepBlock_t* block = &state->v2.blockWorkspace.blocks[i]; - const uint8_t channel = block->channel; - if (channel < PULSE_PROCESSOR_N_BASE_STATIONS) { - pulseProcessorV2SweepBlock_t* previousBlock = &state->v2.blocks[channel]; - if (isBlockPairGood(block, previousBlock)) { - calculateAngles(block, previousBlock, angles); - - *baseStation = channel; - *axis = sweepIdSecond; - angles->measurementType = lighthouseBsTypeV2; - - anglesMeasured = true; - } else { - memcpy(previousBlock, block, sizeof(pulseProcessorV2SweepBlock_t)); - } - } - } - - return anglesMeasured; + // bool anglesMeasured = false; + + // clearStaleAnglesAfterTimeout(angles); + + // int nrOfBlocks = processFrame(frameData, &state->v2.pulseWorkspace, &state->v2.blockWorkspace); + // for (int i = 0; i < nrOfBlocks; i++) { + // const pulseProcessorV2SweepBlock_t* block = &state->v2.blockWorkspace.blocks[i]; + // const uint8_t channel = block->channel; + // if (channel < PULSE_PROCESSOR_N_BASE_STATIONS) { + // pulseProcessorV2SweepBlock_t* previousBlock = &state->v2.blocks[channel]; + // if (isBlockPairGood(block, previousBlock)) { + // calculateAngles(block, previousBlock, angles); + + // *baseStation = channel; + // *axis = sweepIdSecond; + // angles->measurementType = lighthouseBsTypeV2; + + // anglesMeasured = true; + // } else { + // memcpy(previousBlock, block, sizeof(pulseProcessorV2SweepBlock_t)); + // } + // } + // } + + // return anglesMeasured; } bool pulseProcessorV2ProcessPulse(pulseProcessor_t *state, const pulseProcessorFrame_t* frameData, pulseProcessorResult_t* angles, int *baseStation, int *axis, bool* calibDataIsDecoded) { - *calibDataIsDecoded = handleCalibrationData(state, frameData); - return handleAngles(state, frameData, angles, baseStation, axis); + // *calibDataIsDecoded = handleCalibrationData(state, frameData); + // return handleAngles(state, frameData, angles, baseStation, axis); } uint8_t pulseProcessorV2AnglesQuality() { diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Source/include/queue.h b/uboot-compiler/bm_crazyflie/FreeRTOS/Source/include/queue.h index a0439c520..08525a413 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Source/include/queue.h +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Source/include/queue.h @@ -229,7 +229,7 @@ typedef struct QueueDefinition * QueueSetMemberHandle_t; * \ingroup QueueManagement */ #if( configSUPPORT_STATIC_ALLOCATION == 1 ) - #define xQueueCreateStatic( uxQueueLength, uxItemSize, pucQueueStorage, pxQueueBuffer ) xQueueGenericCreateStatic( ( uxQueueLength ), ( uxItemSize ), ( pucQueueStorage ), ( pxQueueBuffer ), ( queueQUEUE_TYPE_BASE ) ) + //#define xQueueCreateStatic( uxQueueLength, uxItemSize, pucQueueStorage, pxQueueBuffer ) xQueueGenericCreateStatic( ( uxQueueLength ), ( uxItemSize ), ( pucQueueStorage ), ( pxQueueBuffer ), ( queueQUEUE_TYPE_BASE ) ) #endif /* configSUPPORT_STATIC_ALLOCATION */ /** diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Source/timers.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Source/timers.c index bfcc4eaff..4b963c8d2 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Source/timers.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Source/timers.c @@ -959,7 +959,7 @@ static void prvCheckForValidListAndQueue( void ) static StaticQueue_t xStaticTimerQueue; /*lint !e956 Ok to declare in this manner to prevent additional conditional compilation guards in other locations. */ static uint8_t ucStaticTimerQueueStorage[ ( size_t ) configTIMER_QUEUE_LENGTH * sizeof( DaemonTaskMessage_t ) ]; /*lint !e956 Ok to declare in this manner to prevent additional conditional compilation guards in other locations. */ - xTimerQueue = xQueueCreateStatic( ( UBaseType_t ) configTIMER_QUEUE_LENGTH, ( UBaseType_t ) sizeof( DaemonTaskMessage_t ), &( ucStaticTimerQueueStorage[ 0 ] ), &xStaticTimerQueue ); + //xTimerQueue = xQueueCreateStatic( ( UBaseType_t ) configTIMER_QUEUE_LENGTH, ( UBaseType_t ) sizeof( DaemonTaskMessage_t ), &( ucStaticTimerQueueStorage[ 0 ] ), &xStaticTimerQueue ); } #else { -- GitLab