From 49441f3832dceb00a8d96e595c87acb0b553f4fe Mon Sep 17 00:00:00 2001 From: 488_MP-4 <488_MP-4@iastate.edu> Date: Thu, 28 Mar 2024 18:02:08 +0100 Subject: [PATCH] commenting --- .../deck/api/deck_analog.c | 85 +- .../deck/api/deck_constants.c | 27 +- .../deck/api/deck_digital.c | 36 +- .../deck/api/deck_spi.c | 325 +++--- .../deck/api/deck_spi3.c | 248 ++--- .../deck/drivers/interface/lpsTdoa2Tag.h | 3 +- .../deck/drivers/interface/lpsTwrTag.h | 3 +- .../deck/drivers/src/activeMarkerDeck.c | 18 +- .../deck/drivers/src/ledring12.c | 44 +- .../deck/drivers/src/locodeck.c | 345 ++++--- .../deck/drivers/src/lpsTdoa2Tag.c | 281 +++--- .../deck/drivers/src/lpsTdoa3Tag.c | 229 ++--- .../deck/drivers/src/lpsTwrTag.c | 690 ++++++------- .../deck/drivers/src/test/exptest.c | 169 ++-- .../deck/drivers/src/test/exptestBolt.c | 273 ++--- .../deck/drivers/src/test/exptestRR.c | 157 +-- .../deck/interface/deck_spi.h | 2 + .../interface/kalman_core/kalman_core.h | 8 +- .../modules/src/crtp_commander_high_level.c | 1 + .../modules/src/kalman_core/kalman_core.c | 953 +++++++++--------- .../src/kalman_core/mm_absolute_height.c | 9 +- .../modules/src/kalman_core/mm_distance.c | 39 +- .../src/kalman_core/mm_distance_robust.c | 331 +++--- .../modules/src/kalman_core/mm_flow.c | 127 +-- .../modules/src/kalman_core/mm_pose.c | 51 +- .../modules/src/kalman_core/mm_position.c | 13 +- .../modules/src/kalman_core/mm_sweep_angles.c | 107 +- .../modules/src/kalman_core/mm_tdoa.c | 119 +-- .../modules/src/kalman_core/mm_tdoa_robust.c | 329 +++--- .../modules/src/kalman_core/mm_tof.c | 41 +- .../modules/src/kalman_core/mm_yaw_error.c | 9 +- .../uart/Makefile | 20 +- .../uart/build/activeMarkerDeck.o | Bin 0 -> 7360 bytes .../uart/build/aideck.o | Bin 0 -> 3952 bytes .../uart/build/bigquad.o | Bin 0 -> 880 bytes .../uart/build/buzzdeck.o | Bin 0 -> 3144 bytes .../uart/build/cfassert.o | Bin 0 -> 3776 bytes .../uart/build/clockCorrectionEngine.o | Bin 0 -> 1848 bytes .../uart/build/cppmdeck.o | Bin 0 -> 2544 bytes .../uart/build/cpuid.o | Bin 0 -> 1016 bytes .../uart/build/crc32.o | Bin 0 -> 2928 bytes .../uart/build/crtp_commander_high_level.o | Bin 0 -> 13512 bytes .../uart/build/debug.o | Bin 0 -> 944 bytes .../uart/build/deck.o | Bin 0 -> 2800 bytes .../uart/build/deck_analog.o | Bin 0 -> 1464 bytes .../uart/build/deck_constants.o | Bin 0 -> 1968 bytes .../uart/build/deck_digital.o | Bin 0 -> 1064 bytes .../uart/build/deck_drivers.o | Bin 0 -> 2704 bytes .../uart/build/deck_info.o | Bin 0 -> 9928 bytes .../uart/build/deck_memory.o | Bin 0 -> 2952 bytes .../uart/build/deck_spi.o | Bin 0 -> 1512 bytes .../uart/build/deck_spi3.o | Bin 0 -> 1496 bytes .../uart/build/deck_test.o | Bin 0 -> 1936 bytes .../uart/build/eprintf.o | Bin 0 -> 3896 bytes .../uart/build/estimator_kalman.o | Bin 0 -> 18520 bytes .../uart/build/exptest.o | Bin 0 -> 1712 bytes .../uart/build/exptestBolt.o | Bin 0 -> 1720 bytes .../uart/build/exptestRR.o | Bin 0 -> 1720 bytes .../uart/build/filter.o | Bin 0 -> 1728 bytes .../uart/build/flowdeck_v1v2.o | Bin 0 -> 8096 bytes .../uart/build/gtgps.o | Bin 0 -> 6920 bytes .../uart/build/health.o | Bin 0 -> 10488 bytes .../uart/build/kalman_core.o | Bin 0 -> 6104 bytes .../uart/build/kalman_supervisor.o | Bin 0 -> 2040 bytes .../uart/build/ledring12.o | Bin 0 -> 19616 bytes .../uart/build/lighthouse.o | Bin 0 -> 3944 bytes .../uart/build/locodeck.o | Bin 0 -> 6896 bytes .../uart/build/lpsTdoa2Tag.o | Bin 0 -> 3520 bytes .../uart/build/lpsTdoa3Tag.o | Bin 0 -> 888 bytes .../uart/build/lpsTwrTag.o | Bin 0 -> 4672 bytes .../uart/build/mm_absolute_height.o | Bin 0 -> 984 bytes .../uart/build/mm_distance.o | Bin 0 -> 968 bytes .../uart/build/mm_distance_robust.o | Bin 0 -> 984 bytes .../uart/build/mm_flow.o | Bin 0 -> 1968 bytes .../uart/build/mm_pose.o | Bin 0 -> 960 bytes .../uart/build/mm_position.o | Bin 0 -> 968 bytes .../uart/build/mm_sweep_angles.o | Bin 0 -> 976 bytes .../uart/build/mm_tdoa.o | Bin 0 -> 960 bytes .../uart/build/mm_tdoa_robust.o | Bin 0 -> 976 bytes .../uart/build/mm_tof.o | Bin 0 -> 960 bytes .../uart/build/mm_yaw_error.o | Bin 0 -> 968 bytes .../uart/build/multiranger.o | Bin 0 -> 11024 bytes .../uart/build/num.o | Bin 0 -> 1744 bytes .../uart/build/oa.o | Bin 0 -> 7504 bytes .../uart/build/outlierFilter.o | Bin 0 -> 3648 bytes .../uart/build/planner.o | Bin 0 -> 3088 bytes .../uart/build/pptraj.o | Bin 0 -> 7888 bytes .../uart/build/pptraj_compressed.o | Bin 0 -> 3296 bytes .../uart/build/tdoaEngine.o | Bin 0 -> 4312 bytes .../uart/build/tdoaEngineInstance.o | Bin 0 -> 16752 bytes .../uart/build/tdoaStats.o | Bin 0 -> 1584 bytes .../uart/build/tdoaStorage.o | Bin 0 -> 3752 bytes .../uart/build/uart.o | Bin 3888 -> 4112 bytes .../uart/build/usddeck.o | Bin 0 -> 23936 bytes .../uart/build/zranger.o | Bin 0 -> 4200 bytes .../uart/build/zranger2.o | Bin 0 -> 6152 bytes .../utils/src/cf_math.h | 7 +- 97 files changed, 2591 insertions(+), 2508 deletions(-) create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/activeMarkerDeck.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/aideck.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/bigquad.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/buzzdeck.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/cfassert.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/clockCorrectionEngine.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/cppmdeck.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/cpuid.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/crc32.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/crtp_commander_high_level.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/debug.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_analog.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_constants.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_digital.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_drivers.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_info.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_memory.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_spi.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_spi3.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_test.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/eprintf.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/estimator_kalman.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/exptest.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/exptestBolt.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/exptestRR.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/filter.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/flowdeck_v1v2.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/gtgps.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/health.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/kalman_core.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/kalman_supervisor.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/ledring12.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/lighthouse.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/locodeck.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/lpsTdoa2Tag.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/lpsTdoa3Tag.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/lpsTwrTag.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_absolute_height.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_distance.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_distance_robust.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_flow.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_pose.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_position.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_sweep_angles.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_tdoa.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_tdoa_robust.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_tof.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_yaw_error.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/multiranger.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/num.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/oa.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/outlierFilter.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/planner.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/pptraj.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/pptraj_compressed.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/tdoaEngine.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/tdoaEngineInstance.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/tdoaStats.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/tdoaStorage.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/usddeck.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/zranger.o create mode 100644 uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/zranger2.o diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/api/deck_analog.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/api/deck_analog.c index 27fed2489..6296ff178 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/api/deck_analog.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/api/deck_analog.c @@ -68,13 +68,14 @@ void adcInit(void) static uint16_t analogReadChannel(uint8_t channel) { /* According to datasheet, minimum sampling time for 12-bit conversion is 15 cycles. */ - ADC_RegularChannelConfig(ADC2, channel, 1, ADC_SampleTime_15Cycles); + //COMMENTED FIRMWARE + // ADC_RegularChannelConfig(ADC2, channel, 1, ADC_SampleTime_15Cycles); - /* Start the conversion */ - ADC_SoftwareStartConv(ADC2); + // /* Start the conversion */ + // ADC_SoftwareStartConv(ADC2); - /* Wait until conversion completion */ - while(ADC_GetFlagStatus(ADC2, ADC_FLAG_EOC) == RESET); + // /* Wait until conversion completion */ + // while(ADC_GetFlagStatus(ADC2, ADC_FLAG_EOC) == RESET); /* Get the conversion value */ return ADC_GetConversionValue(ADC2); @@ -82,25 +83,26 @@ static uint16_t analogReadChannel(uint8_t channel) uint16_t analogRead(const deckPin_t pin) { - assert_param(deckGPIOMapping[pin.id].adcCh > -1); + //COMMENTED FIRMWARE + // assert_param(deckGPIOMapping[pin.id].adcCh > -1); - /* Now set the GPIO pin to analog mode. */ + // /* Now set the GPIO pin to analog mode. */ - /* Enable clock for the peripheral of the pin.*/ - RCC_AHB1PeriphClockCmd(deckGPIOMapping[pin.id].periph, ENABLE); + // /* Enable clock for the peripheral of the pin.*/ + // RCC_AHB1PeriphClockCmd(deckGPIOMapping[pin.id].periph, ENABLE); - /* Populate structure with RESET values. */ - GPIO_InitTypeDef GPIO_InitStructure; - GPIO_StructInit(&GPIO_InitStructure); + // /* Populate structure with RESET values. */ + // GPIO_InitTypeDef GPIO_InitStructure; + // GPIO_StructInit(&GPIO_InitStructure); - /* Initialise the GPIO pin to analog mode. */ - GPIO_InitStructure.GPIO_Pin = deckGPIOMapping[pin.id].pin; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AN; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_25MHz; - GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; + // /* Initialise the GPIO pin to analog mode. */ + // GPIO_InitStructure.GPIO_Pin = deckGPIOMapping[pin.id].pin; + // GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AN; + // GPIO_InitStructure.GPIO_Speed = GPIO_Speed_25MHz; + // GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; /* TODO: Any settling time before we can do ADC after init on the GPIO pin? */ - GPIO_Init(deckGPIOMapping[pin.id].port, &GPIO_InitStructure); + // GPIO_Init(deckGPIOMapping[pin.id].port, &GPIO_InitStructure); /* Read the appropriate ADC channel. */ return analogReadChannel((uint8_t)deckGPIOMapping[pin.id].adcCh); @@ -117,29 +119,30 @@ void analogReference(uint8_t type) void analogReadResolution(uint8_t bits) { - ADC_InitTypeDef ADC_InitStructure; - - assert_param((bits >= 6) && (bits <= 12)); - - adcRange = 1 << bits; - switch (bits) - { - case 12: stregResolution = ADC_Resolution_12b; break; - case 10: stregResolution = ADC_Resolution_10b; break; - case 8: stregResolution = ADC_Resolution_8b; break; - case 6: stregResolution = ADC_Resolution_6b; break; - default: stregResolution = ADC_Resolution_12b; break; - } - - /* Init ADC2 witch new resolution */ - ADC_InitStructure.ADC_Resolution = stregResolution; - ADC_InitStructure.ADC_ScanConvMode = DISABLE; - ADC_InitStructure.ADC_ContinuousConvMode = DISABLE; - ADC_InitStructure.ADC_ExternalTrigConvEdge = 0; - ADC_InitStructure.ADC_ExternalTrigConv = 0; - ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right; - ADC_InitStructure.ADC_NbrOfConversion = 1; - ADC_Init(ADC2, &ADC_InitStructure); + //COMMENTED FIRMWARE + // ADC_InitTypeDef ADC_InitStructure; + + // assert_param((bits >= 6) && (bits <= 12)); + + // adcRange = 1 << bits; + // switch (bits) + // { + // case 12: stregResolution = ADC_Resolution_12b; break; + // case 10: stregResolution = ADC_Resolution_10b; break; + // case 8: stregResolution = ADC_Resolution_8b; break; + // case 6: stregResolution = ADC_Resolution_6b; break; + // default: stregResolution = ADC_Resolution_12b; break; + // } + + // /* Init ADC2 witch new resolution */ + // ADC_InitStructure.ADC_Resolution = stregResolution; + // ADC_InitStructure.ADC_ScanConvMode = DISABLE; + // ADC_InitStructure.ADC_ContinuousConvMode = DISABLE; + // ADC_InitStructure.ADC_ExternalTrigConvEdge = 0; + // ADC_InitStructure.ADC_ExternalTrigConv = 0; + // ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right; + // ADC_InitStructure.ADC_NbrOfConversion = 1; + // ADC_Init(ADC2, &ADC_InitStructure); } float analogReadVoltage(const deckPin_t pin) diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/api/deck_constants.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/api/deck_constants.c index b7e31e8d8..b49d8d7fd 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/api/deck_constants.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/api/deck_constants.c @@ -28,19 +28,20 @@ /* Mapping between Deck Pin number, real GPIO and ADC channel */ deckGPIOMapping_t deckGPIOMapping[13] = { - {.periph= RCC_AHB1Periph_GPIOC, .port= GPIOC, .pin=GPIO_Pin_11, .adcCh=-1}, /* RX1 */ - {.periph= RCC_AHB1Periph_GPIOC, .port= GPIOC, .pin=GPIO_Pin_10, .adcCh=-1}, /* TX1 */ - {.periph= RCC_AHB1Periph_GPIOB, .port= GPIOB, .pin=GPIO_Pin_7, .adcCh=-1}, /* SDA */ - {.periph= RCC_AHB1Periph_GPIOB, .port= GPIOB, .pin=GPIO_Pin_6, .adcCh=-1}, /* SCL */ - {.periph= RCC_AHB1Periph_GPIOB, .port= GPIOB, .pin=GPIO_Pin_8, .adcCh=-1}, /* IO1 */ - {.periph= RCC_AHB1Periph_GPIOB, .port= GPIOB, .pin=GPIO_Pin_5, .adcCh=-1}, /* IO2 */ - {.periph= RCC_AHB1Periph_GPIOB, .port= GPIOB, .pin=GPIO_Pin_4, .adcCh=-1}, /* IO3 */ - {.periph= RCC_AHB1Periph_GPIOC, .port= GPIOC, .pin=GPIO_Pin_12, .adcCh=-1}, /* IO4 */ - {.periph= RCC_AHB1Periph_GPIOA, .port= GPIOA, .pin=GPIO_Pin_2, .adcCh=ADC_Channel_2}, /* TX2 */ - {.periph= RCC_AHB1Periph_GPIOA, .port= GPIOA, .pin=GPIO_Pin_3, .adcCh=ADC_Channel_3}, /* RX2 */ - {.periph= RCC_AHB1Periph_GPIOA, .port= GPIOA, .pin=GPIO_Pin_5, .adcCh=ADC_Channel_5}, /* SCK */ - {.periph= RCC_AHB1Periph_GPIOA, .port= GPIOA, .pin=GPIO_Pin_6, .adcCh=ADC_Channel_6}, /* MISO */ - {.periph= RCC_AHB1Periph_GPIOA, .port= GPIOA, .pin=GPIO_Pin_7, .adcCh=ADC_Channel_7}, /* MOSI */ + //COMMENTED FIRMWARE + // {.periph= RCC_AHB1Periph_GPIOC, .port= GPIOC, .pin=GPIO_Pin_11, .adcCh=-1}, /* RX1 */ + // {.periph= RCC_AHB1Periph_GPIOC, .port= GPIOC, .pin=GPIO_Pin_10, .adcCh=-1}, /* TX1 */ + // {.periph= RCC_AHB1Periph_GPIOB, .port= GPIOB, .pin=GPIO_Pin_7, .adcCh=-1}, /* SDA */ + // {.periph= RCC_AHB1Periph_GPIOB, .port= GPIOB, .pin=GPIO_Pin_6, .adcCh=-1}, /* SCL */ + // {.periph= RCC_AHB1Periph_GPIOB, .port= GPIOB, .pin=GPIO_Pin_8, .adcCh=-1}, /* IO1 */ + // {.periph= RCC_AHB1Periph_GPIOB, .port= GPIOB, .pin=GPIO_Pin_5, .adcCh=-1}, /* IO2 */ + // {.periph= RCC_AHB1Periph_GPIOB, .port= GPIOB, .pin=GPIO_Pin_4, .adcCh=-1}, /* IO3 */ + // {.periph= RCC_AHB1Periph_GPIOC, .port= GPIOC, .pin=GPIO_Pin_12, .adcCh=-1}, /* IO4 */ + // {.periph= RCC_AHB1Periph_GPIOA, .port= GPIOA, .pin=GPIO_Pin_2, .adcCh=ADC_Channel_2}, /* TX2 */ + // {.periph= RCC_AHB1Periph_GPIOA, .port= GPIOA, .pin=GPIO_Pin_3, .adcCh=ADC_Channel_3}, /* RX2 */ + // {.periph= RCC_AHB1Periph_GPIOA, .port= GPIOA, .pin=GPIO_Pin_5, .adcCh=ADC_Channel_5}, /* SCK */ + // {.periph= RCC_AHB1Periph_GPIOA, .port= GPIOA, .pin=GPIO_Pin_6, .adcCh=ADC_Channel_6}, /* MISO */ + // {.periph= RCC_AHB1Periph_GPIOA, .port= GPIOA, .pin=GPIO_Pin_7, .adcCh=ADC_Channel_7}, /* MOSI */ }; // Pin definitions diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/api/deck_digital.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/api/deck_digital.c index b8ae72c85..d0944da42 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/api/deck_digital.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/api/deck_digital.c @@ -30,31 +30,35 @@ void pinMode(const deckPin_t pin, const uint32_t mode) { - RCC_AHB1PeriphClockCmd(deckGPIOMapping[pin.id].periph, ENABLE); + //COMMENTED FIRMWARE + // RCC_AHB1PeriphClockCmd(deckGPIOMapping[pin.id].periph, ENABLE); - GPIO_InitTypeDef GPIO_InitStructure = {0}; + // GPIO_InitTypeDef GPIO_InitStructure = {0}; - GPIO_InitStructure.GPIO_Pin = deckGPIOMapping[pin.id].pin; - GPIO_InitStructure.GPIO_Mode = (mode == OUTPUT) ? GPIO_Mode_OUT:GPIO_Mode_IN; - if (mode == OUTPUT) GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - if (mode == INPUT_PULLUP) GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; - if (mode == INPUT_PULLDOWN) GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_25MHz; - GPIO_Init(deckGPIOMapping[pin.id].port, &GPIO_InitStructure); + // GPIO_InitStructure.GPIO_Pin = deckGPIOMapping[pin.id].pin; + // GPIO_InitStructure.GPIO_Mode = (mode == OUTPUT) ? GPIO_Mode_OUT:GPIO_Mode_IN; + // if (mode == OUTPUT) GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + // if (mode == INPUT_PULLUP) GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; + // if (mode == INPUT_PULLDOWN) GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN; + // GPIO_InitStructure.GPIO_Speed = GPIO_Speed_25MHz; + // GPIO_Init(deckGPIOMapping[pin.id].port, &GPIO_InitStructure); } void digitalWrite(const deckPin_t pin, const uint32_t val) { - BitAction action = Bit_RESET; - if (val) { - action = Bit_SET; - } + //COMMENTED FIRMWARE + // BitAction action = Bit_RESET; + // if (val) { + // action = Bit_SET; + // } - GPIO_WriteBit(deckGPIOMapping[pin.id].port, deckGPIOMapping[pin.id].pin, action); + // GPIO_WriteBit(deckGPIOMapping[pin.id].port, deckGPIOMapping[pin.id].pin, action); } int digitalRead(const deckPin_t pin) { - int val = GPIO_ReadInputDataBit(deckGPIOMapping[pin.id].port, deckGPIOMapping[pin.id].pin); - return (val==Bit_SET)?HIGH:LOW; + //COMMENTED FIRMWARE + // int val = GPIO_ReadInputDataBit(deckGPIOMapping[pin.id].port, deckGPIOMapping[pin.id].pin); + // return (val==Bit_SET)?HIGH:LOW; + return 0; } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/api/deck_spi.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/api/deck_spi.c index df9cd9ce6..6aff3645d 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/api/deck_spi.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/api/deck_spi.c @@ -93,127 +93,130 @@ static void spiConfigureWithSpeed(uint16_t baudRatePrescaler); void spiBegin(void) { - GPIO_InitTypeDef GPIO_InitStructure; + //COMMENTED FIRMWARE +// GPIO_InitTypeDef GPIO_InitStructure; - // binary semaphores created using xSemaphoreCreateBinary() are created in a state - // such that the the semaphore must first be 'given' before it can be 'taken' - txComplete = xSemaphoreCreateBinary(); - rxComplete = xSemaphoreCreateBinary(); - spiMutex = xSemaphoreCreateMutex(); +// // binary semaphores created using xSemaphoreCreateBinary() are created in a state +// // such that the the semaphore must first be 'given' before it can be 'taken' +// txComplete = xSemaphoreCreateBinary(); +// rxComplete = xSemaphoreCreateBinary(); +// spiMutex = xSemaphoreCreateMutex(); - /*!< Enable the SPI clock */ - SPI_CLK_INIT(SPI_CLK, ENABLE); +// /*!< Enable the SPI clock */ +// SPI_CLK_INIT(SPI_CLK, ENABLE); - /*!< Enable GPIO clocks */ - RCC_AHB1PeriphClockCmd(SPI_SCK_GPIO_CLK | SPI_MISO_GPIO_CLK | - SPI_MOSI_GPIO_CLK, ENABLE); +// /*!< Enable GPIO clocks */ +// RCC_AHB1PeriphClockCmd(SPI_SCK_GPIO_CLK | SPI_MISO_GPIO_CLK | +// SPI_MOSI_GPIO_CLK, ENABLE); - /*!< Enable DMA Clocks */ - SPI_DMA_CLK_INIT(SPI_DMA_CLK, ENABLE); +// /*!< Enable DMA Clocks */ +// SPI_DMA_CLK_INIT(SPI_DMA_CLK, ENABLE); - /*!< SPI pins configuration *************************************************/ +// /*!< SPI pins configuration *************************************************/ - /*!< Connect SPI pins to AF5 */ - GPIO_PinAFConfig(SPI_SCK_GPIO_PORT, SPI_SCK_SOURCE, SPI_SCK_AF); - GPIO_PinAFConfig(SPI_MISO_GPIO_PORT, SPI_MISO_SOURCE, SPI_MISO_AF); - GPIO_PinAFConfig(SPI_MOSI_GPIO_PORT, SPI_MOSI_SOURCE, SPI_MOSI_AF); +// /*!< Connect SPI pins to AF5 */ +// GPIO_PinAFConfig(SPI_SCK_GPIO_PORT, SPI_SCK_SOURCE, SPI_SCK_AF); +// GPIO_PinAFConfig(SPI_MISO_GPIO_PORT, SPI_MISO_SOURCE, SPI_MISO_AF); +// GPIO_PinAFConfig(SPI_MOSI_GPIO_PORT, SPI_MOSI_SOURCE, SPI_MOSI_AF); - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; -#ifdef DECK_SPI_MODE3 - GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; -#else - GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN; -#endif +// GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; +// GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; +// GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; +// #ifdef DECK_SPI_MODE3 +// GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; +// #else +// GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN; +// #endif - /*!< SPI SCK pin configuration */ - GPIO_InitStructure.GPIO_Pin = SPI_SCK_PIN; - GPIO_Init(SPI_SCK_GPIO_PORT, &GPIO_InitStructure); +// /*!< SPI SCK pin configuration */ +// GPIO_InitStructure.GPIO_Pin = SPI_SCK_PIN; +// GPIO_Init(SPI_SCK_GPIO_PORT, &GPIO_InitStructure); - /*!< SPI MOSI pin configuration */ - GPIO_InitStructure.GPIO_Pin = SPI_MOSI_PIN; - GPIO_Init(SPI_MOSI_GPIO_PORT, &GPIO_InitStructure); +// /*!< SPI MOSI pin configuration */ +// GPIO_InitStructure.GPIO_Pin = SPI_MOSI_PIN; +// GPIO_Init(SPI_MOSI_GPIO_PORT, &GPIO_InitStructure); - /*!< SPI MISO pin configuration */ - GPIO_InitStructure.GPIO_Pin = SPI_MISO_PIN; - GPIO_Init(SPI_MISO_GPIO_PORT, &GPIO_InitStructure); +// /*!< SPI MISO pin configuration */ +// GPIO_InitStructure.GPIO_Pin = SPI_MISO_PIN; +// GPIO_Init(SPI_MISO_GPIO_PORT, &GPIO_InitStructure); - /*!< SPI DMA Initialization */ - spiDMAInit(); +// /*!< SPI DMA Initialization */ +// spiDMAInit(); - /*!< SPI configuration */ - spiConfigureWithSpeed(SPI_BAUDRATE_2MHZ); +// /*!< SPI configuration */ +// spiConfigureWithSpeed(SPI_BAUDRATE_2MHZ); - isInit = true; +// isInit = true; } static void spiDMAInit() { - DMA_InitTypeDef DMA_InitStructure; - NVIC_InitTypeDef NVIC_InitStructure; - - /* Configure DMA Initialization Structure */ - DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Disable ; - DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ; - DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single ; - DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; - DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; - DMA_InitStructure.DMA_Mode = DMA_Mode_Normal; - DMA_InitStructure.DMA_PeripheralBaseAddr =(uint32_t) (&(SPI->DR)) ; - DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single; - DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; - DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; - DMA_InitStructure.DMA_Priority = DMA_Priority_High; - DMA_InitStructure.DMA_BufferSize = 0; // set later - DMA_InitStructure.DMA_Memory0BaseAddr = 0; // set later - - // Configure TX DMA - DMA_InitStructure.DMA_Channel = SPI_TX_DMA_CHANNEL; - DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral; - DMA_Cmd(SPI_TX_DMA_STREAM,DISABLE); - DMA_Init(SPI_TX_DMA_STREAM, &DMA_InitStructure); - - // Configure RX DMA - DMA_InitStructure.DMA_Channel = SPI_RX_DMA_CHANNEL; - DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory; - DMA_Cmd(SPI_RX_DMA_STREAM,DISABLE); - DMA_Init(SPI_RX_DMA_STREAM, &DMA_InitStructure); - - // Configure interrupts - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_HIGH_PRI; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - - NVIC_InitStructure.NVIC_IRQChannel = SPI_TX_DMA_IRQ; - NVIC_Init(&NVIC_InitStructure); - - NVIC_InitStructure.NVIC_IRQChannel = SPI_RX_DMA_IRQ; - NVIC_Init(&NVIC_InitStructure); + //COMMENTED FIRMWARE + // DMA_InitTypeDef DMA_InitStructure; + // NVIC_InitTypeDef NVIC_InitStructure; + + // /* Configure DMA Initialization Structure */ + // DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Disable ; + // DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ; + // DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single ; + // DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; + // DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; + // DMA_InitStructure.DMA_Mode = DMA_Mode_Normal; + // DMA_InitStructure.DMA_PeripheralBaseAddr =(uint32_t) (&(SPI->DR)) ; + // DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single; + // DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; + // DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; + // DMA_InitStructure.DMA_Priority = DMA_Priority_High; + // DMA_InitStructure.DMA_BufferSize = 0; // set later + // DMA_InitStructure.DMA_Memory0BaseAddr = 0; // set later + + // // Configure TX DMA + // DMA_InitStructure.DMA_Channel = SPI_TX_DMA_CHANNEL; + // DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral; + // DMA_Cmd(SPI_TX_DMA_STREAM,DISABLE); + // DMA_Init(SPI_TX_DMA_STREAM, &DMA_InitStructure); + + // // Configure RX DMA + // DMA_InitStructure.DMA_Channel = SPI_RX_DMA_CHANNEL; + // DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory; + // DMA_Cmd(SPI_RX_DMA_STREAM,DISABLE); + // DMA_Init(SPI_RX_DMA_STREAM, &DMA_InitStructure); + + // // Configure interrupts + // NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_HIGH_PRI; + // NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; + // NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + + // NVIC_InitStructure.NVIC_IRQChannel = SPI_TX_DMA_IRQ; + // NVIC_Init(&NVIC_InitStructure); + + // NVIC_InitStructure.NVIC_IRQChannel = SPI_RX_DMA_IRQ; + // NVIC_Init(&NVIC_InitStructure); } static void spiConfigureWithSpeed(uint16_t baudRatePrescaler) { - SPI_InitTypeDef SPI_InitStructure; - - SPI_I2S_DeInit(SPI); - - SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex; - SPI_InitStructure.SPI_Mode = SPI_Mode_Master; - SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b; -#ifdef DECK_SPI_MODE3 - SPI_InitStructure.SPI_CPOL = SPI_CPOL_High; - SPI_InitStructure.SPI_CPHA = SPI_CPHA_2Edge; -#else - SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low; - SPI_InitStructure.SPI_CPHA = SPI_CPHA_1Edge; -#endif - SPI_InitStructure.SPI_NSS = SPI_NSS_Soft; - SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB; - SPI_InitStructure.SPI_CRCPolynomial = 0; // Not used - - SPI_InitStructure.SPI_BaudRatePrescaler = baudRatePrescaler; - SPI_Init(SPI, &SPI_InitStructure); + //COMMENTED FIRMWARE +// SPI_InitTypeDef SPI_InitStructure; + +// SPI_I2S_DeInit(SPI); + +// SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex; +// SPI_InitStructure.SPI_Mode = SPI_Mode_Master; +// SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b; +// #ifdef DECK_SPI_MODE3 +// SPI_InitStructure.SPI_CPOL = SPI_CPOL_High; +// SPI_InitStructure.SPI_CPHA = SPI_CPHA_2Edge; +// #else +// SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low; +// SPI_InitStructure.SPI_CPHA = SPI_CPHA_1Edge; +// #endif +// SPI_InitStructure.SPI_NSS = SPI_NSS_Soft; +// SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB; +// SPI_InitStructure.SPI_CRCPolynomial = 0; // Not used + +// SPI_InitStructure.SPI_BaudRatePrescaler = baudRatePrescaler; +// SPI_Init(SPI, &SPI_InitStructure); } bool spiTest(void) @@ -223,42 +226,44 @@ bool spiTest(void) bool spiExchange(size_t length, const uint8_t * data_tx, uint8_t * data_rx) { - ASSERT_DMA_SAFE(data_tx); - ASSERT_DMA_SAFE(data_rx); + //COMMENTED FIRMWARE + // ASSERT_DMA_SAFE(data_tx); + // ASSERT_DMA_SAFE(data_rx); - // DMA already configured, just need to set memory addresses - SPI_TX_DMA_STREAM->M0AR = (uint32_t)data_tx; - SPI_TX_DMA_STREAM->NDTR = length; + // // DMA already configured, just need to set memory addresses + // SPI_TX_DMA_STREAM->M0AR = (uint32_t)data_tx; + // SPI_TX_DMA_STREAM->NDTR = length; - SPI_RX_DMA_STREAM->M0AR = (uint32_t)data_rx; - SPI_RX_DMA_STREAM->NDTR = length; + // SPI_RX_DMA_STREAM->M0AR = (uint32_t)data_rx; + // SPI_RX_DMA_STREAM->NDTR = length; - // Enable SPI DMA Interrupts - DMA_ITConfig(SPI_TX_DMA_STREAM, DMA_IT_TC, ENABLE); - DMA_ITConfig(SPI_RX_DMA_STREAM, DMA_IT_TC, ENABLE); + // // Enable SPI DMA Interrupts + // DMA_ITConfig(SPI_TX_DMA_STREAM, DMA_IT_TC, ENABLE); + // DMA_ITConfig(SPI_RX_DMA_STREAM, DMA_IT_TC, ENABLE); - // Clear DMA Flags - DMA_ClearFlag(SPI_TX_DMA_STREAM, DMA_FLAG_FEIF5|DMA_FLAG_DMEIF5|DMA_FLAG_TEIF5|DMA_FLAG_HTIF5|DMA_FLAG_TCIF5); - DMA_ClearFlag(SPI_RX_DMA_STREAM, DMA_FLAG_FEIF0|DMA_FLAG_DMEIF0|DMA_FLAG_TEIF0|DMA_FLAG_HTIF0|DMA_FLAG_TCIF0); + // // Clear DMA Flags + // DMA_ClearFlag(SPI_TX_DMA_STREAM, DMA_FLAG_FEIF5|DMA_FLAG_DMEIF5|DMA_FLAG_TEIF5|DMA_FLAG_HTIF5|DMA_FLAG_TCIF5); + // DMA_ClearFlag(SPI_RX_DMA_STREAM, DMA_FLAG_FEIF0|DMA_FLAG_DMEIF0|DMA_FLAG_TEIF0|DMA_FLAG_HTIF0|DMA_FLAG_TCIF0); - // Enable DMA Streams - DMA_Cmd(SPI_TX_DMA_STREAM,ENABLE); - DMA_Cmd(SPI_RX_DMA_STREAM,ENABLE); + // // Enable DMA Streams + // DMA_Cmd(SPI_TX_DMA_STREAM,ENABLE); + // DMA_Cmd(SPI_RX_DMA_STREAM,ENABLE); - // Enable SPI DMA requests - SPI_I2S_DMACmd(SPI, SPI_I2S_DMAReq_Tx, ENABLE); - SPI_I2S_DMACmd(SPI, SPI_I2S_DMAReq_Rx, ENABLE); + // // Enable SPI DMA requests + // SPI_I2S_DMACmd(SPI, SPI_I2S_DMAReq_Tx, ENABLE); + // SPI_I2S_DMACmd(SPI, SPI_I2S_DMAReq_Rx, ENABLE); - // Enable peripheral - SPI_Cmd(SPI, ENABLE); + // // Enable peripheral + // SPI_Cmd(SPI, ENABLE); - // Wait for completion - bool result = (xSemaphoreTake(txComplete, portMAX_DELAY) == pdTRUE) - && (xSemaphoreTake(rxComplete, portMAX_DELAY) == pdTRUE); + // // Wait for completion + // bool result = (xSemaphoreTake(txComplete, portMAX_DELAY) == pdTRUE) + // && (xSemaphoreTake(rxComplete, portMAX_DELAY) == pdTRUE); - // Disable peripheral - SPI_Cmd(SPI, DISABLE); - return result; + // // Disable peripheral + // SPI_Cmd(SPI, DISABLE); + //return result; + return false; } void spiBeginTransaction(uint16_t baudRatePrescaler) @@ -274,52 +279,54 @@ void spiEndTransaction() void __attribute__((used)) SPI_TX_DMA_IRQHandler(void) { - portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + //COMMENTED FIRMWARE + // portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; - // Stop and cleanup DMA stream - DMA_ITConfig(SPI_TX_DMA_STREAM, DMA_IT_TC, DISABLE); - DMA_ClearITPendingBit(SPI_TX_DMA_STREAM, SPI_TX_DMA_FLAG_TCIF); + // // Stop and cleanup DMA stream + // DMA_ITConfig(SPI_TX_DMA_STREAM, DMA_IT_TC, DISABLE); + // DMA_ClearITPendingBit(SPI_TX_DMA_STREAM, SPI_TX_DMA_FLAG_TCIF); - // Clear stream flags - DMA_ClearFlag(SPI_TX_DMA_STREAM,SPI_TX_DMA_FLAG_TCIF); + // // Clear stream flags + // DMA_ClearFlag(SPI_TX_DMA_STREAM,SPI_TX_DMA_FLAG_TCIF); - // Disable SPI DMA requests - SPI_I2S_DMACmd(SPI, SPI_I2S_DMAReq_Tx, DISABLE); + // // Disable SPI DMA requests + // SPI_I2S_DMACmd(SPI, SPI_I2S_DMAReq_Tx, DISABLE); - // Disable streams - DMA_Cmd(SPI_TX_DMA_STREAM,DISABLE); + // // Disable streams + // DMA_Cmd(SPI_TX_DMA_STREAM,DISABLE); - // Give the semaphore, allowing the SPI transaction to complete - xSemaphoreGiveFromISR(txComplete, &xHigherPriorityTaskWoken); + // // Give the semaphore, allowing the SPI transaction to complete + // xSemaphoreGiveFromISR(txComplete, &xHigherPriorityTaskWoken); - if (xHigherPriorityTaskWoken) - { - portYIELD(); - } + // if (xHigherPriorityTaskWoken) + // { + // portYIELD(); + // } } void __attribute__((used)) SPI_RX_DMA_IRQHandler(void) { - portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + //COMMENTED FIRMWARE + // portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; - // Stop and cleanup DMA stream - DMA_ITConfig(SPI_RX_DMA_STREAM, DMA_IT_TC, DISABLE); - DMA_ClearITPendingBit(SPI_RX_DMA_STREAM, SPI_RX_DMA_FLAG_TCIF); + // // Stop and cleanup DMA stream + // DMA_ITConfig(SPI_RX_DMA_STREAM, DMA_IT_TC, DISABLE); + // DMA_ClearITPendingBit(SPI_RX_DMA_STREAM, SPI_RX_DMA_FLAG_TCIF); - // Clear stream flags - DMA_ClearFlag(SPI_RX_DMA_STREAM,SPI_RX_DMA_FLAG_TCIF); + // // Clear stream flags + // DMA_ClearFlag(SPI_RX_DMA_STREAM,SPI_RX_DMA_FLAG_TCIF); - // Disable SPI DMA requests - SPI_I2S_DMACmd(SPI, SPI_I2S_DMAReq_Rx, DISABLE); + // // Disable SPI DMA requests + // SPI_I2S_DMACmd(SPI, SPI_I2S_DMAReq_Rx, DISABLE); - // Disable streams - DMA_Cmd(SPI_RX_DMA_STREAM,DISABLE); + // // Disable streams + // DMA_Cmd(SPI_RX_DMA_STREAM,DISABLE); - // Give the semaphore, allowing the SPI transaction to complete - xSemaphoreGiveFromISR(rxComplete, &xHigherPriorityTaskWoken); + // // Give the semaphore, allowing the SPI transaction to complete + // xSemaphoreGiveFromISR(rxComplete, &xHigherPriorityTaskWoken); - if (xHigherPriorityTaskWoken) - { - portYIELD(); - } + // if (xHigherPriorityTaskWoken) + // { + // portYIELD(); + // } } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/api/deck_spi3.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/api/deck_spi3.c index 75bb87026..4b16d397d 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/api/deck_spi3.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/api/deck_spi3.c @@ -94,118 +94,120 @@ static void spi3ConfigureWithSpeed(uint16_t baudRatePrescaler); void spi3Begin(void) { - GPIO_InitTypeDef GPIO_InitStructure; + //COMMENTED FIRMWARE + // GPIO_InitTypeDef GPIO_InitStructure; - // binary semaphores created using xSemaphoreCreateBinary() are created in a state - // such that the the semaphore must first be 'given' before it can be 'taken' - txComplete = xSemaphoreCreateBinary(); - rxComplete = xSemaphoreCreateBinary(); - spiMutex = xSemaphoreCreateMutex(); + // // binary semaphores created using xSemaphoreCreateBinary() are created in a state + // // such that the the semaphore must first be 'given' before it can be 'taken' + // txComplete = xSemaphoreCreateBinary(); + // rxComplete = xSemaphoreCreateBinary(); + // spiMutex = xSemaphoreCreateMutex(); - /*!< Enable the SPI clock */ - SPI_CLK_INIT(SPI_CLK, ENABLE); + // /*!< Enable the SPI clock */ + // SPI_CLK_INIT(SPI_CLK, ENABLE); - /*!< Enable GPIO clocks */ - RCC_AHB1PeriphClockCmd(SPI_SCK_GPIO_CLK | SPI_MISO_GPIO_CLK | - SPI_MOSI_GPIO_CLK, ENABLE); + // /*!< Enable GPIO clocks */ + // RCC_AHB1PeriphClockCmd(SPI_SCK_GPIO_CLK | SPI_MISO_GPIO_CLK | + // SPI_MOSI_GPIO_CLK, ENABLE); - /*!< Enable DMA Clocks */ - SPI_DMA_CLK_INIT(SPI_DMA_CLK, ENABLE); + // /*!< Enable DMA Clocks */ + // SPI_DMA_CLK_INIT(SPI_DMA_CLK, ENABLE); - /*!< SPI pins configuration *************************************************/ + // /*!< SPI pins configuration *************************************************/ - /*!< Connect SPI pins to AF5 */ - GPIO_PinAFConfig(SPI_SCK_GPIO_PORT, SPI_SCK_SOURCE, SPI_SCK_AF); - GPIO_PinAFConfig(SPI_MISO_GPIO_PORT, SPI_MISO_SOURCE, SPI_MISO_AF); - GPIO_PinAFConfig(SPI_MOSI_GPIO_PORT, SPI_MOSI_SOURCE, SPI_MOSI_AF); + // /*!< Connect SPI pins to AF5 */ + // GPIO_PinAFConfig(SPI_SCK_GPIO_PORT, SPI_SCK_SOURCE, SPI_SCK_AF); + // GPIO_PinAFConfig(SPI_MISO_GPIO_PORT, SPI_MISO_SOURCE, SPI_MISO_AF); + // GPIO_PinAFConfig(SPI_MOSI_GPIO_PORT, SPI_MOSI_SOURCE, SPI_MOSI_AF); - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN; + // GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; + // GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + // GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + // GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN; - /*!< SPI SCK pin configuration */ - GPIO_InitStructure.GPIO_Pin = SPI_SCK_PIN; - GPIO_Init(SPI_SCK_GPIO_PORT, &GPIO_InitStructure); + // /*!< SPI SCK pin configuration */ + // GPIO_InitStructure.GPIO_Pin = SPI_SCK_PIN; + // GPIO_Init(SPI_SCK_GPIO_PORT, &GPIO_InitStructure); - /*!< SPI MOSI pin configuration */ - GPIO_InitStructure.GPIO_Pin = SPI_MOSI_PIN; - GPIO_Init(SPI_MOSI_GPIO_PORT, &GPIO_InitStructure); + // /*!< SPI MOSI pin configuration */ + // GPIO_InitStructure.GPIO_Pin = SPI_MOSI_PIN; + // GPIO_Init(SPI_MOSI_GPIO_PORT, &GPIO_InitStructure); - /*!< SPI MISO pin configuration */ - GPIO_InitStructure.GPIO_Pin = SPI_MISO_PIN; - GPIO_Init(SPI_MISO_GPIO_PORT, &GPIO_InitStructure); + // /*!< SPI MISO pin configuration */ + // GPIO_InitStructure.GPIO_Pin = SPI_MISO_PIN; + // GPIO_Init(SPI_MISO_GPIO_PORT, &GPIO_InitStructure); - /*!< SPI DMA Initialization */ - spi3DMAInit(); + // /*!< SPI DMA Initialization */ + // spi3DMAInit(); - /*!< SPI configuration */ - spi3ConfigureWithSpeed(SPI_BAUDRATE_2MHZ); + // /*!< SPI configuration */ + // spi3ConfigureWithSpeed(SPI_BAUDRATE_2MHZ); - isInit = true; + // isInit = true; } static void spi3DMAInit() { - DMA_InitTypeDef DMA_InitStructure; - NVIC_InitTypeDef NVIC_InitStructure; - - /* Configure DMA Initialization Structure */ - DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Disable ; - DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ; - DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single ; - DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; - DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; - DMA_InitStructure.DMA_Mode = DMA_Mode_Normal; - DMA_InitStructure.DMA_PeripheralBaseAddr =(uint32_t) (&(SPI->DR)) ; - DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single; - DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; - DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; - DMA_InitStructure.DMA_Priority = DMA_Priority_High; - DMA_InitStructure.DMA_BufferSize = 0; // set later - DMA_InitStructure.DMA_Memory0BaseAddr = 0; // set later - - // Configure TX DMA - DMA_InitStructure.DMA_Channel = SPI_TX_DMA_CHANNEL; - DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral; - DMA_Cmd(SPI_TX_DMA_STREAM,DISABLE); - DMA_Init(SPI_TX_DMA_STREAM, &DMA_InitStructure); - - // Configure RX DMA - DMA_InitStructure.DMA_Channel = SPI_RX_DMA_CHANNEL; - DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory; - DMA_Cmd(SPI_RX_DMA_STREAM,DISABLE); - DMA_Init(SPI_RX_DMA_STREAM, &DMA_InitStructure); - - // Configure interrupts - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_HIGH_PRI; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - - NVIC_InitStructure.NVIC_IRQChannel = SPI_TX_DMA_IRQ; - NVIC_Init(&NVIC_InitStructure); - - NVIC_InitStructure.NVIC_IRQChannel = SPI_RX_DMA_IRQ; - NVIC_Init(&NVIC_InitStructure); -} - -static void spi3ConfigureWithSpeed(uint16_t baudRatePrescaler) -{ - SPI_InitTypeDef SPI_InitStructure; - - SPI_I2S_DeInit(SPI); - - SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex; - SPI_InitStructure.SPI_Mode = SPI_Mode_Master; - SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b; - SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low; - SPI_InitStructure.SPI_CPHA = SPI_CPHA_1Edge; - SPI_InitStructure.SPI_NSS = SPI_NSS_Soft; - SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB; - SPI_InitStructure.SPI_CRCPolynomial = 0; // Not used - - SPI_InitStructure.SPI_BaudRatePrescaler = baudRatePrescaler; - SPI_Init(SPI, &SPI_InitStructure); + //COMMENTED FIRMWARE +// DMA_InitTypeDef DMA_InitStructure; +// NVIC_InitTypeDef NVIC_InitStructure; + +// /* Configure DMA Initialization Structure */ +// DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Disable ; +// DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ; +// DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single ; +// DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; +// DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; +// DMA_InitStructure.DMA_Mode = DMA_Mode_Normal; +// DMA_InitStructure.DMA_PeripheralBaseAddr =(uint32_t) (&(SPI->DR)) ; +// DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single; +// DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; +// DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; +// DMA_InitStructure.DMA_Priority = DMA_Priority_High; +// DMA_InitStructure.DMA_BufferSize = 0; // set later +// DMA_InitStructure.DMA_Memory0BaseAddr = 0; // set later + +// // Configure TX DMA +// DMA_InitStructure.DMA_Channel = SPI_TX_DMA_CHANNEL; +// DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral; +// DMA_Cmd(SPI_TX_DMA_STREAM,DISABLE); +// DMA_Init(SPI_TX_DMA_STREAM, &DMA_InitStructure); + +// // Configure RX DMA +// DMA_InitStructure.DMA_Channel = SPI_RX_DMA_CHANNEL; +// DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory; +// DMA_Cmd(SPI_RX_DMA_STREAM,DISABLE); +// DMA_Init(SPI_RX_DMA_STREAM, &DMA_InitStructure); + +// // Configure interrupts +// NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_HIGH_PRI; +// NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; +// NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + +// NVIC_InitStructure.NVIC_IRQChannel = SPI_TX_DMA_IRQ; +// NVIC_Init(&NVIC_InitStructure); + +// NVIC_InitStructure.NVIC_IRQChannel = SPI_RX_DMA_IRQ; +// NVIC_Init(&NVIC_InitStructure); +// } + +// static void spi3ConfigureWithSpeed(uint16_t baudRatePrescaler) +// { +// SPI_InitTypeDef SPI_InitStructure; + +// SPI_I2S_DeInit(SPI); + +// SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex; +// SPI_InitStructure.SPI_Mode = SPI_Mode_Master; +// SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b; +// SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low; +// SPI_InitStructure.SPI_CPHA = SPI_CPHA_1Edge; +// SPI_InitStructure.SPI_NSS = SPI_NSS_Soft; +// SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB; +// SPI_InitStructure.SPI_CRCPolynomial = 0; // Not used + +// SPI_InitStructure.SPI_BaudRatePrescaler = baudRatePrescaler; +// SPI_Init(SPI, &SPI_InitStructure); } bool spi3Test(void) @@ -215,42 +217,44 @@ bool spi3Test(void) bool spi3Exchange(size_t length, const uint8_t * data_tx, uint8_t * data_rx) { - ASSERT_DMA_SAFE(data_tx); - ASSERT_DMA_SAFE(data_rx); + //COMMENTED FIRMWARE + // ASSERT_DMA_SAFE(data_tx); + // ASSERT_DMA_SAFE(data_rx); - // DMA already configured, just need to set memory addresses - SPI_TX_DMA_STREAM->M0AR = (uint32_t)data_tx; - SPI_TX_DMA_STREAM->NDTR = length; + // // DMA already configured, just need to set memory addresses + // SPI_TX_DMA_STREAM->M0AR = (uint32_t)data_tx; + // SPI_TX_DMA_STREAM->NDTR = length; - SPI_RX_DMA_STREAM->M0AR = (uint32_t)data_rx; - SPI_RX_DMA_STREAM->NDTR = length; + // SPI_RX_DMA_STREAM->M0AR = (uint32_t)data_rx; + // SPI_RX_DMA_STREAM->NDTR = length; - // Enable SPI DMA Interrupts - DMA_ITConfig(SPI_TX_DMA_STREAM, DMA_IT_TC, ENABLE); - DMA_ITConfig(SPI_RX_DMA_STREAM, DMA_IT_TC, ENABLE); + // // Enable SPI DMA Interrupts + // DMA_ITConfig(SPI_TX_DMA_STREAM, DMA_IT_TC, ENABLE); + // DMA_ITConfig(SPI_RX_DMA_STREAM, DMA_IT_TC, ENABLE); - // Clear DMA Flags - DMA_ClearFlag(SPI_TX_DMA_STREAM, DMA_FLAG_FEIF7|DMA_FLAG_DMEIF7|DMA_FLAG_TEIF7|DMA_FLAG_HTIF7|DMA_FLAG_TCIF7); - DMA_ClearFlag(SPI_RX_DMA_STREAM, DMA_FLAG_FEIF0|DMA_FLAG_DMEIF0|DMA_FLAG_TEIF0|DMA_FLAG_HTIF0|DMA_FLAG_TCIF0); + // // Clear DMA Flags + // DMA_ClearFlag(SPI_TX_DMA_STREAM, DMA_FLAG_FEIF7|DMA_FLAG_DMEIF7|DMA_FLAG_TEIF7|DMA_FLAG_HTIF7|DMA_FLAG_TCIF7); + // DMA_ClearFlag(SPI_RX_DMA_STREAM, DMA_FLAG_FEIF0|DMA_FLAG_DMEIF0|DMA_FLAG_TEIF0|DMA_FLAG_HTIF0|DMA_FLAG_TCIF0); - // Enable DMA Streams - DMA_Cmd(SPI_TX_DMA_STREAM,ENABLE); - DMA_Cmd(SPI_RX_DMA_STREAM,ENABLE); + // // Enable DMA Streams + // DMA_Cmd(SPI_TX_DMA_STREAM,ENABLE); + // DMA_Cmd(SPI_RX_DMA_STREAM,ENABLE); - // Enable SPI DMA requests - SPI_I2S_DMACmd(SPI, SPI_I2S_DMAReq_Tx, ENABLE); - SPI_I2S_DMACmd(SPI, SPI_I2S_DMAReq_Rx, ENABLE); + // // Enable SPI DMA requests + // SPI_I2S_DMACmd(SPI, SPI_I2S_DMAReq_Tx, ENABLE); + // SPI_I2S_DMACmd(SPI, SPI_I2S_DMAReq_Rx, ENABLE); - // Enable peripheral - SPI_Cmd(SPI, ENABLE); + // // Enable peripheral + // SPI_Cmd(SPI, ENABLE); - // Wait for completion - bool result = (xSemaphoreTake(txComplete, portMAX_DELAY) == pdTRUE) - && (xSemaphoreTake(rxComplete, portMAX_DELAY) == pdTRUE); + // // Wait for completion + // bool result = (xSemaphoreTake(txComplete, portMAX_DELAY) == pdTRUE) + // && (xSemaphoreTake(rxComplete, portMAX_DELAY) == pdTRUE); - // Disable peripheral - SPI_Cmd(SPI, DISABLE); - return result; + // // Disable peripheral + // SPI_Cmd(SPI, DISABLE); + // return result; + return false; } void spi3BeginTransaction(uint16_t baudRatePrescaler) diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/interface/lpsTdoa2Tag.h b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/interface/lpsTdoa2Tag.h index c0f76596e..258ed19b6 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/interface/lpsTdoa2Tag.h +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/interface/lpsTdoa2Tag.h @@ -2,7 +2,8 @@ #define __LPS_TDOA2_TAG_H__ #include "locodeck.h" -#include "libdw1000.h" +//COMMENTED FIRMWARE +//#include "libdw1000.h" #include "mac.h" diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/interface/lpsTwrTag.h b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/interface/lpsTwrTag.h index f37681914..a8ade7985 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/interface/lpsTwrTag.h +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/interface/lpsTwrTag.h @@ -2,7 +2,8 @@ #define __LPS_TWR_TAG_H__ #include "locodeck.h" -#include "libdw1000.h" +//COMMENTED FIRMWARE +//#include "libdw1000.h" #include "mac.h" diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/activeMarkerDeck.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/activeMarkerDeck.c index dfa07af32..b5d1ecf58 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/activeMarkerDeck.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/activeMarkerDeck.c @@ -70,7 +70,8 @@ static uint8_t requestedDeckMode = MODE_QUALISYS; static uint8_t doPollDeckButtonSensor = 0; static uint8_t deckButtonSensorValue = 0; static uint32_t nextPollTime = 0; -static const uint32_t pollIntervall = M2T(100); +//COMMENTED FIRMWARE +//static const uint32_t pollIntervall = M2T(100); static bool i2cOk = false; // defines eventTrigger_activeMarkerModeChanged @@ -161,13 +162,14 @@ static void handleModeUpdate() { } static void handleButtonSensorRead() { - if (doPollDeckButtonSensor) { - uint32_t now = xTaskGetTickCount(); - if (now > nextPollTime) { - i2cdevReadReg8(I2C1_DEV, DECK_I2C_ADDRESS, MEM_ADR_BUTTON_SENSOR, 1, &deckButtonSensorValue); - nextPollTime = now + pollIntervall; - } - } + //COMMENTED FIRMWARE + // if (doPollDeckButtonSensor) { + // uint32_t now = xTaskGetTickCount(); + // if (now > nextPollTime) { + // i2cdevReadReg8(I2C1_DEV, DECK_I2C_ADDRESS, MEM_ADR_BUTTON_SENSOR, 1, &deckButtonSensorValue); + // nextPollTime = now + pollIntervall; + // } + // } } static void task(void *param) { diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/ledring12.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/ledring12.c index 4a86f542d..8386b88a7 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/ledring12.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/ledring12.c @@ -564,10 +564,11 @@ static void brightnessEffect(uint8_t buffer[][3], bool reset) static void setHeadlightsOn(bool on) { - if (on) - GPIO_SetBits(GPIOB, GPIO_Pin_4); - else - GPIO_ResetBits(GPIOB, GPIO_Pin_4); + //COMMENTED FIRMWARE + // if (on) + // GPIO_SetBits(GPIOB, GPIO_Pin_4); + // else + // GPIO_ResetBits(GPIOB, GPIO_Pin_4); } @@ -1045,30 +1046,31 @@ static void ledring12Timer(xTimerHandle timer) static void ledring12Init(DeckInfo *info) { - if (isInit) { - return; - } + //COMMENTED FIRMWARE + // if (isInit) { + // return; + // } - GPIO_InitTypeDef GPIO_InitStructure; + // GPIO_InitTypeDef GPIO_InitStructure; - ws2812Init(); + // ws2812Init(); - neffect = sizeof(effectsFct)/sizeof(effectsFct[0])-1; + // neffect = sizeof(effectsFct)/sizeof(effectsFct[0])-1; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; - GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4; - GPIO_Init(GPIOB, &GPIO_InitStructure); + // GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; + // GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + // GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; + // GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4; + // GPIO_Init(GPIOB, &GPIO_InitStructure); - memoryRegisterHandler(&ledringmemDef); - memoryRegisterHandler(&timingmemDef); + // memoryRegisterHandler(&ledringmemDef); + // memoryRegisterHandler(&timingmemDef); - isInit = true; + // isInit = true; - timer = xTimerCreate( "ringTimer", M2T(50), - pdTRUE, NULL, ledring12Timer ); - xTimerStart(timer, 100); + // timer = xTimerCreate( "ringTimer", M2T(50), + // pdTRUE, NULL, ledring12Timer ); + // xTimerStart(timer, 100); } static bool handleLedringmemRead(const uint32_t memAddr, const uint8_t readLen, uint8_t* buffer) { diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/locodeck.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/locodeck.c index 21a788f23..d06338755 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/locodeck.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/locodeck.c @@ -127,8 +127,10 @@ static uwbAlgorithm_t *algorithm = &uwbTwrTagAlgorithm; static bool isInit = false; static TaskHandle_t uwbTaskHandle = 0; static SemaphoreHandle_t algoSemaphore; -static dwDevice_t dwm_device; -static dwDevice_t *dwm = &dwm_device; + +//COMMENTED FIRMWARE +// static dwDevice_t dwm_device; +// static dwDevice_t *dwm = &dwm_device; static QueueHandle_t lppShortQueue; @@ -161,19 +163,20 @@ static const MemoryHandlerDef_t memDef = { }; static void buildAnchorMemList(const uint32_t memAddr, const uint8_t readLen, uint8_t* dest, const uint32_t pageBase_address, const uint8_t anchorCount, const uint8_t unsortedAnchorList[]); -static void txCallback(dwDevice_t *dev) -{ - timeout = algorithm->onEvent(dev, eventPacketSent); -} +//COMMENTED FIRMWARE +// static void txCallback(dwDevice_t *dev) +// { +// timeout = algorithm->onEvent(dev, eventPacketSent); +// } -static void rxCallback(dwDevice_t *dev) -{ - timeout = algorithm->onEvent(dev, eventPacketReceived); -} +// static void rxCallback(dwDevice_t *dev) +// { +// timeout = algorithm->onEvent(dev, eventPacketReceived); +// } -static void rxTimeoutCallback(dwDevice_t * dev) { - timeout = algorithm->onEvent(dev, eventReceiveTimeout); -} +// static void rxTimeoutCallback(dwDevice_t * dev) { +// timeout = algorithm->onEvent(dev, eventReceiveTimeout); +// } static bool handleMemRead(const uint32_t memAddr, const uint8_t readLen, uint8_t* dest) { bool result = false; @@ -275,16 +278,16 @@ uint8_t locoDeckGetActiveAnchorIdList(uint8_t unorderedAnchorList[], const int m static bool switchToMode(const lpsMode_t newMode) { bool result = false; + //COMMENTED FIRMWARE + // if (lpsMode_auto != newMode && newMode <= LPS_NUMBER_OF_ALGORITHMS) { + // algoOptions.currentRangingMode = newMode; + // algorithm = algorithmsList[algoOptions.currentRangingMode].algorithm; - if (lpsMode_auto != newMode && newMode <= LPS_NUMBER_OF_ALGORITHMS) { - algoOptions.currentRangingMode = newMode; - algorithm = algorithmsList[algoOptions.currentRangingMode].algorithm; + // algorithm->init(dwm); + // timeout = algorithm->onEvent(dwm, eventTimeout); - algorithm->init(dwm); - timeout = algorithm->onEvent(dwm, eventTimeout); - - result = true; - } + // result = true; + // } return result; } @@ -345,29 +348,30 @@ static void handleModeSwitch() { } static void uwbTask(void* parameters) { - lppShortQueue = xQueueCreate(10, sizeof(lpsLppShortPacket_t)); - - algoOptions.currentRangingMode = lpsMode_auto; - - systemWaitStart(); - - while(1) { - xSemaphoreTake(algoSemaphore, portMAX_DELAY); - handleModeSwitch(); - xSemaphoreGive(algoSemaphore); - - if (ulTaskNotifyTake(pdTRUE, timeout / portTICK_PERIOD_MS) > 0) { - do{ - xSemaphoreTake(algoSemaphore, portMAX_DELAY); - dwHandleInterrupt(dwm); - xSemaphoreGive(algoSemaphore); - } while(digitalRead(GPIO_PIN_IRQ) != 0); - } else { - xSemaphoreTake(algoSemaphore, portMAX_DELAY); - timeout = algorithm->onEvent(dwm, eventTimeout); - xSemaphoreGive(algoSemaphore); - } - } + //COMMENTED FIRMWARE + // lppShortQueue = xQueueCreate(10, sizeof(lpsLppShortPacket_t)); + + // algoOptions.currentRangingMode = lpsMode_auto; + + // systemWaitStart(); + + // while(1) { + // xSemaphoreTake(algoSemaphore, portMAX_DELAY); + // handleModeSwitch(); + // xSemaphoreGive(algoSemaphore); + + // if (ulTaskNotifyTake(pdTRUE, timeout / portTICK_PERIOD_MS) > 0) { + // do{ + // xSemaphoreTake(algoSemaphore, portMAX_DELAY); + // dwHandleInterrupt(dwm); + // xSemaphoreGive(algoSemaphore); + // } while(digitalRead(GPIO_PIN_IRQ) != 0); + // } else { + // xSemaphoreTake(algoSemaphore, portMAX_DELAY); + // timeout = algorithm->onEvent(dwm, eventTimeout); + // xSemaphoreGive(algoSemaphore); + // } + // } } static lpsLppShortPacket_t lppShortPacket; @@ -397,152 +401,159 @@ static uint8_t spiRxBuffer[196]; static uint16_t spiSpeed = SPI_BAUDRATE_2MHZ; /************ Low level ops for libdw **********/ -static void spiWrite(dwDevice_t* dev, const void *header, size_t headerLength, - const void* data, size_t dataLength) -{ - spiBeginTransaction(spiSpeed); - digitalWrite(CS_PIN, LOW); - memcpy(spiTxBuffer, header, headerLength); - memcpy(spiTxBuffer+headerLength, data, dataLength); - spiExchange(headerLength+dataLength, spiTxBuffer, spiRxBuffer); - digitalWrite(CS_PIN, HIGH); - spiEndTransaction(); - STATS_CNT_RATE_EVENT(&spiWriteCount); -} +//COMMENTED FIRMWARE +// static void spiWrite(dwDevice_t* dev, const void *header, size_t headerLength, +// const void* data, size_t dataLength) +// { +// spiBeginTransaction(spiSpeed); +// digitalWrite(CS_PIN, LOW); +// memcpy(spiTxBuffer, header, headerLength); +// memcpy(spiTxBuffer+headerLength, data, dataLength); +// spiExchange(headerLength+dataLength, spiTxBuffer, spiRxBuffer); +// digitalWrite(CS_PIN, HIGH); +// spiEndTransaction(); +// STATS_CNT_RATE_EVENT(&spiWriteCount); +// } + +//COMMENTED FIRMWARE +// static void spiRead(dwDevice_t* dev, const void *header, size_t headerLength, +// void* data, size_t dataLength) +// { +// spiBeginTransaction(spiSpeed); +// digitalWrite(CS_PIN, LOW); +// memcpy(spiTxBuffer, header, headerLength); +// memset(spiTxBuffer+headerLength, 0, dataLength); +// spiExchange(headerLength+dataLength, spiTxBuffer, spiRxBuffer); +// memcpy(data, spiRxBuffer+headerLength, dataLength); +// digitalWrite(CS_PIN, HIGH); +// spiEndTransaction(); +// STATS_CNT_RATE_EVENT(&spiReadCount); +// } + +// #if LOCODECK_USE_ALT_PINS +// void __attribute__((used)) EXTI5_Callback(void) +// #else +// void __attribute__((used)) EXTI11_Callback(void) +// #endif +// { +// portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + +// // Unlock interrupt handling task +// vTaskNotifyGiveFromISR(uwbTaskHandle, &xHigherPriorityTaskWoken); + +// if(xHigherPriorityTaskWoken) { +// portYIELD(); +// } +// } + +//COMMENTED FIRMWARE +// static void spiSetSpeed(dwDevice_t* dev, dwSpiSpeed_t speed) +// { +// if (speed == dwSpiSpeedLow) +// { +// spiSpeed = SPI_BAUDRATE_2MHZ; +// } +// else if (speed == dwSpiSpeedHigh) +// { +// spiSpeed = SPI_BAUDRATE_21MHZ; +// } +// } + + +//COMMENTED FIRMWARE +// static void delayms(dwDevice_t* dev, unsigned int delay) +// { +// vTaskDelay(M2T(delay)); +// } + +//COMMENTED FIRMWARE +// static dwOps_t dwOps = { +// .spiRead = spiRead, +// .spiWrite = spiWrite, +// .spiSetSpeed = spiSetSpeed, +// .delayms = delayms, +// }; -static void spiRead(dwDevice_t* dev, const void *header, size_t headerLength, - void* data, size_t dataLength) -{ - spiBeginTransaction(spiSpeed); - digitalWrite(CS_PIN, LOW); - memcpy(spiTxBuffer, header, headerLength); - memset(spiTxBuffer+headerLength, 0, dataLength); - spiExchange(headerLength+dataLength, spiTxBuffer, spiRxBuffer); - memcpy(data, spiRxBuffer+headerLength, dataLength); - digitalWrite(CS_PIN, HIGH); - spiEndTransaction(); - STATS_CNT_RATE_EVENT(&spiReadCount); -} +/*********** Deck driver initialization ***************/ -#if LOCODECK_USE_ALT_PINS - void __attribute__((used)) EXTI5_Callback(void) -#else - void __attribute__((used)) EXTI11_Callback(void) -#endif - { - portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; +static void dwm1000Init(DeckInfo *info) +{ + //COMMENTED FIRMWARE + // EXTI_InitTypeDef EXTI_InitStructure; - // Unlock interrupt handling task - vTaskNotifyGiveFromISR(uwbTaskHandle, &xHigherPriorityTaskWoken); + // spiBegin(); - if(xHigherPriorityTaskWoken) { - portYIELD(); - } - } + // // Set up interrupt + // SYSCFG_EXTILineConfig(EXTI_PortSource, EXTI_PinSource); -static void spiSetSpeed(dwDevice_t* dev, dwSpiSpeed_t speed) -{ - if (speed == dwSpiSpeedLow) - { - spiSpeed = SPI_BAUDRATE_2MHZ; - } - else if (speed == dwSpiSpeedHigh) - { - spiSpeed = SPI_BAUDRATE_21MHZ; - } -} + // EXTI_InitStructure.EXTI_Line = EXTI_LineN; + // EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt; + // EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising; + // EXTI_InitStructure.EXTI_LineCmd = ENABLE; + // EXTI_Init(&EXTI_InitStructure); -static void delayms(dwDevice_t* dev, unsigned int delay) -{ - vTaskDelay(M2T(delay)); -} + // // Init pins + // pinMode(CS_PIN, OUTPUT); + // pinMode(GPIO_PIN_RESET, OUTPUT); + // pinMode(GPIO_PIN_IRQ, INPUT); -static dwOps_t dwOps = { - .spiRead = spiRead, - .spiWrite = spiWrite, - .spiSetSpeed = spiSetSpeed, - .delayms = delayms, -}; + // // Reset the DW1000 chip + // digitalWrite(GPIO_PIN_RESET, 0); + // vTaskDelay(M2T(10)); + // digitalWrite(GPIO_PIN_RESET, 1); + // vTaskDelay(M2T(10)); -/*********** Deck driver initialization ***************/ + // // Initialize the driver + // dwInit(dwm, &dwOps); // Init libdw -static void dwm1000Init(DeckInfo *info) -{ - EXTI_InitTypeDef EXTI_InitStructure; - - spiBegin(); - - // Set up interrupt - SYSCFG_EXTILineConfig(EXTI_PortSource, EXTI_PinSource); - - EXTI_InitStructure.EXTI_Line = EXTI_LineN; - EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt; - EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising; - EXTI_InitStructure.EXTI_LineCmd = ENABLE; - EXTI_Init(&EXTI_InitStructure); - - // Init pins - pinMode(CS_PIN, OUTPUT); - pinMode(GPIO_PIN_RESET, OUTPUT); - pinMode(GPIO_PIN_IRQ, INPUT); - - // Reset the DW1000 chip - digitalWrite(GPIO_PIN_RESET, 0); - vTaskDelay(M2T(10)); - digitalWrite(GPIO_PIN_RESET, 1); - vTaskDelay(M2T(10)); - - // Initialize the driver - dwInit(dwm, &dwOps); // Init libdw - - int result = dwConfigure(dwm); - if (result != 0) { - isInit = false; - DEBUG_PRINT("Failed to configure DW1000!\r\n"); - return; - } + // int result = dwConfigure(dwm); + // if (result != 0) { + // isInit = false; + // DEBUG_PRINT("Failed to configure DW1000!\r\n"); + // return; + // } - dwEnableAllLeds(dwm); + // dwEnableAllLeds(dwm); - dwTime_t delay = {.full = 0}; - dwSetAntenaDelay(dwm, delay); + // dwTime_t delay = {.full = 0}; + // dwSetAntenaDelay(dwm, delay); - dwAttachSentHandler(dwm, txCallback); - dwAttachReceivedHandler(dwm, rxCallback); - dwAttachReceiveTimeoutHandler(dwm, rxTimeoutCallback); + // dwAttachSentHandler(dwm, txCallback); + // dwAttachReceivedHandler(dwm, rxCallback); + // dwAttachReceiveTimeoutHandler(dwm, rxTimeoutCallback); - dwNewConfiguration(dwm); - dwSetDefaults(dwm); + // dwNewConfiguration(dwm); + // dwSetDefaults(dwm); - #ifdef LPS_LONGER_RANGE - dwEnableMode(dwm, MODE_SHORTDATA_MID_ACCURACY); - #else - dwEnableMode(dwm, MODE_SHORTDATA_FAST_ACCURACY); - #endif + // #ifdef LPS_LONGER_RANGE + // dwEnableMode(dwm, MODE_SHORTDATA_MID_ACCURACY); + // #else + // dwEnableMode(dwm, MODE_SHORTDATA_FAST_ACCURACY); + // #endif - dwSetChannel(dwm, CHANNEL_2); - dwSetPreambleCode(dwm, PREAMBLE_CODE_64MHZ_9); + // dwSetChannel(dwm, CHANNEL_2); + // dwSetPreambleCode(dwm, PREAMBLE_CODE_64MHZ_9); - #ifdef LPS_FULL_TX_POWER - dwUseSmartPower(dwm, false); - dwSetTxPower(dwm, 0x1F1F1F1Ful); - #else - dwUseSmartPower(dwm, true); - #endif + // #ifdef LPS_FULL_TX_POWER + // dwUseSmartPower(dwm, false); + // dwSetTxPower(dwm, 0x1F1F1F1Ful); + // #else + // dwUseSmartPower(dwm, true); + // #endif - dwSetReceiveWaitTimeout(dwm, DEFAULT_RX_TIMEOUT); + // dwSetReceiveWaitTimeout(dwm, DEFAULT_RX_TIMEOUT); - dwCommitConfiguration(dwm); + // dwCommitConfiguration(dwm); - memoryRegisterHandler(&memDef); + // memoryRegisterHandler(&memDef); - algoSemaphore= xSemaphoreCreateMutex(); + // algoSemaphore= xSemaphoreCreateMutex(); - xTaskCreate(uwbTask, LPS_DECK_TASK_NAME, 3 * configMINIMAL_STACK_SIZE, NULL, - LPS_DECK_TASK_PRI, &uwbTaskHandle); + // xTaskCreate(uwbTask, LPS_DECK_TASK_NAME, 3 * configMINIMAL_STACK_SIZE, NULL, + // LPS_DECK_TASK_PRI, &uwbTaskHandle); - isInit = true; + // isInit = true; } uint16_t locoDeckGetRangingState() { diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/lpsTdoa2Tag.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/lpsTdoa2Tag.c index a49993f78..8239867dd 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/lpsTdoa2Tag.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/lpsTdoa2Tag.c @@ -151,127 +151,128 @@ static void handleLppPacket(const int dataLength, const packet_t* rxPacket, tdoa } // Send an LPP packet, the radio will automatically go back in RX mode -static void sendLppShort(dwDevice_t *dev, lpsLppShortPacket_t *packet) -{ - static packet_t txPacket; - dwIdle(dev); - - MAC80215_PACKET_INIT(txPacket, MAC802154_TYPE_DATA); - - txPacket.payload[LPS_TDOA2_TYPE_INDEX] = LPP_HEADER_SHORT_PACKET; - memcpy(&txPacket.payload[LPS_TDOA2_SEND_LPP_PAYLOAD_INDEX], packet->data, packet->length); - - txPacket.pan = 0xbccf; - txPacket.sourceAddress = 0xbccf000000000000 | 0xff; - txPacket.destAddress = options->anchorAddress[packet->dest]; - - dwNewTransmit(dev); - dwSetDefaults(dev); - dwSetData(dev, (uint8_t*)&txPacket, MAC802154_HEADER_LENGTH+1+packet->length); - - dwWaitForResponse(dev, true); - dwStartTransmit(dev); -} - -static bool rxcallback(dwDevice_t *dev) { - tdoaStats_t* stats = &tdoaEngineState.stats; - STATS_CNT_RATE_EVENT(&stats->packetsReceived); - - int dataLength = dwGetDataLength(dev); - packet_t rxPacket; - - dwGetData(dev, (uint8_t*)&rxPacket, dataLength); - const rangePacket2_t* packet = (rangePacket2_t*)rxPacket.payload; - - bool lppSent = false; - if (packet->type == PACKET_TYPE_TDOA2) { - const uint8_t anchor = rxPacket.sourceAddress & 0xff; - - // Check if we need to send the current LPP packet - if (lppPacketToSend && lppPacket.dest == anchor) { - sendLppShort(dev, &lppPacket); - lppSent = true; - } - - dwTime_t arrival = {.full = 0}; - dwGetReceiveTimestamp(dev, &arrival); - - if (anchor < LOCODECK_NR_OF_TDOA2_ANCHORS) { - uint32_t now_ms = T2M(xTaskGetTickCount()); - - const int64_t rxAn_by_T_in_cl_T = arrival.full; - const int64_t txAn_in_cl_An = packet->timestamps[anchor]; - const uint8_t seqNr = packet->sequenceNrs[anchor] & 0x7f; - - tdoaAnchorContext_t anchorCtx; - tdoaEngineGetAnchorCtxForPacketProcessing(&tdoaEngineState, anchor, now_ms, &anchorCtx); - updateRemoteData(&anchorCtx, packet); - tdoaEngineProcessPacket(&tdoaEngineState, &anchorCtx, txAn_in_cl_An, rxAn_by_T_in_cl_T); - tdoaStorageSetRxTxData(&anchorCtx, rxAn_by_T_in_cl_T, txAn_in_cl_An, seqNr); - - logClockCorrection[anchor] = tdoaStorageGetClockCorrection(&anchorCtx); - - previousAnchor = anchor; - - handleLppPacket(dataLength, &rxPacket, &anchorCtx); - - rangingOk = true; - } - } - - return lppSent; -} - -static void setRadioInReceiveMode(dwDevice_t *dev) { - dwNewReceive(dev); - dwSetDefaults(dev); - dwStartReceive(dev); -} - -static uint32_t onEvent(dwDevice_t *dev, uwbEvent_t event) { - switch(event) { - case eventPacketReceived: - if (rxcallback(dev)) { - lppPacketToSend = false; - } else { - setRadioInReceiveMode(dev); - - // Discard lpp packet if we cannot send it for too long - if (++lppPacketSendTryCounter >= TDOA2_LPP_PACKET_SEND_TIMEOUT) { - lppPacketToSend = false; - } - } - - if (!lppPacketToSend) { - // Get next lpp packet - lppPacketToSend = lpsGetLppShort(&lppPacket); - lppPacketSendTryCounter = 0; - } - break; - case eventTimeout: - setRadioInReceiveMode(dev); - break; - case eventReceiveTimeout: - setRadioInReceiveMode(dev); - break; - case eventPacketSent: - // Service packet sent, the radio is back to receive automatically - break; - default: - ASSERT_FAILED(); - } - - uint32_t now = xTaskGetTickCount(); - uint16_t rangingState = 0; - for (int anchor = 0; anchor < LOCODECK_NR_OF_TDOA2_ANCHORS; anchor++) { - if (now < history[anchor].anchorStatusTimeout) { - rangingState |= (1 << anchor); - } - } - locoDeckSetRangingState(rangingState); - - return MAX_TIMEOUT; -} +//COMMENTED FIRMWARE +// static void sendLppShort(dwDevice_t *dev, lpsLppShortPacket_t *packet) +// { +// static packet_t txPacket; +// dwIdle(dev); + +// MAC80215_PACKET_INIT(txPacket, MAC802154_TYPE_DATA); + +// txPacket.payload[LPS_TDOA2_TYPE_INDEX] = LPP_HEADER_SHORT_PACKET; +// memcpy(&txPacket.payload[LPS_TDOA2_SEND_LPP_PAYLOAD_INDEX], packet->data, packet->length); + +// txPacket.pan = 0xbccf; +// txPacket.sourceAddress = 0xbccf000000000000 | 0xff; +// txPacket.destAddress = options->anchorAddress[packet->dest]; + +// dwNewTransmit(dev); +// dwSetDefaults(dev); +// dwSetData(dev, (uint8_t*)&txPacket, MAC802154_HEADER_LENGTH+1+packet->length); + +// dwWaitForResponse(dev, true); +// dwStartTransmit(dev); +// } + +// static bool rxcallback(dwDevice_t *dev) { +// tdoaStats_t* stats = &tdoaEngineState.stats; +// STATS_CNT_RATE_EVENT(&stats->packetsReceived); + +// int dataLength = dwGetDataLength(dev); +// packet_t rxPacket; + +// dwGetData(dev, (uint8_t*)&rxPacket, dataLength); +// const rangePacket2_t* packet = (rangePacket2_t*)rxPacket.payload; + +// bool lppSent = false; +// if (packet->type == PACKET_TYPE_TDOA2) { +// const uint8_t anchor = rxPacket.sourceAddress & 0xff; + +// // Check if we need to send the current LPP packet +// if (lppPacketToSend && lppPacket.dest == anchor) { +// sendLppShort(dev, &lppPacket); +// lppSent = true; +// } + +// dwTime_t arrival = {.full = 0}; +// dwGetReceiveTimestamp(dev, &arrival); + +// if (anchor < LOCODECK_NR_OF_TDOA2_ANCHORS) { +// uint32_t now_ms = T2M(xTaskGetTickCount()); + +// const int64_t rxAn_by_T_in_cl_T = arrival.full; +// const int64_t txAn_in_cl_An = packet->timestamps[anchor]; +// const uint8_t seqNr = packet->sequenceNrs[anchor] & 0x7f; + +// tdoaAnchorContext_t anchorCtx; +// tdoaEngineGetAnchorCtxForPacketProcessing(&tdoaEngineState, anchor, now_ms, &anchorCtx); +// updateRemoteData(&anchorCtx, packet); +// tdoaEngineProcessPacket(&tdoaEngineState, &anchorCtx, txAn_in_cl_An, rxAn_by_T_in_cl_T); +// tdoaStorageSetRxTxData(&anchorCtx, rxAn_by_T_in_cl_T, txAn_in_cl_An, seqNr); + +// logClockCorrection[anchor] = tdoaStorageGetClockCorrection(&anchorCtx); + +// previousAnchor = anchor; + +// handleLppPacket(dataLength, &rxPacket, &anchorCtx); + +// rangingOk = true; +// } +// } + +// return lppSent; +// } + +// static void setRadioInReceiveMode(dwDevice_t *dev) { +// dwNewReceive(dev); +// dwSetDefaults(dev); +// dwStartReceive(dev); +// } + +// static uint32_t onEvent(dwDevice_t *dev, uwbEvent_t event) { +// switch(event) { +// case eventPacketReceived: +// if (rxcallback(dev)) { +// lppPacketToSend = false; +// } else { +// setRadioInReceiveMode(dev); + +// // Discard lpp packet if we cannot send it for too long +// if (++lppPacketSendTryCounter >= TDOA2_LPP_PACKET_SEND_TIMEOUT) { +// lppPacketToSend = false; +// } +// } + +// if (!lppPacketToSend) { +// // Get next lpp packet +// lppPacketToSend = lpsGetLppShort(&lppPacket); +// lppPacketSendTryCounter = 0; +// } +// break; +// case eventTimeout: +// setRadioInReceiveMode(dev); +// break; +// case eventReceiveTimeout: +// setRadioInReceiveMode(dev); +// break; +// case eventPacketSent: +// // Service packet sent, the radio is back to receive automatically +// break; +// default: +// ASSERT_FAILED(); +// } + +// uint32_t now = xTaskGetTickCount(); +// uint16_t rangingState = 0; +// for (int anchor = 0; anchor < LOCODECK_NR_OF_TDOA2_ANCHORS; anchor++) { +// if (now < history[anchor].anchorStatusTimeout) { +// rangingState |= (1 << anchor); +// } +// } +// locoDeckSetRangingState(rangingState); + +// return MAX_TIMEOUT; +// } static void sendTdoaToEstimatorCallback(tdoaMeasurement_t* tdoaMeasurement) { @@ -294,22 +295,22 @@ static void sendTdoaToEstimatorCallback(tdoaMeasurement_t* tdoaMeasurement) { } } +//COMMENTED FIRMWARE +// static void Initialize(dwDevice_t *dev) { +// uint32_t now_ms = T2M(xTaskGetTickCount()); +// tdoaEngineInit(&tdoaEngineState, now_ms, sendTdoaToEstimatorCallback, LOCODECK_TS_FREQ, TdoaEngineMatchingAlgorithmYoungest); -static void Initialize(dwDevice_t *dev) { - uint32_t now_ms = T2M(xTaskGetTickCount()); - tdoaEngineInit(&tdoaEngineState, now_ms, sendTdoaToEstimatorCallback, LOCODECK_TS_FREQ, TdoaEngineMatchingAlgorithmYoungest); +// previousAnchor = 0; - previousAnchor = 0; +// lppPacketToSend = false; - lppPacketToSend = false; +// locoDeckSetRangingState(0); +// dwSetReceiveWaitTimeout(dev, TDOA2_RECEIVE_TIMEOUT); - locoDeckSetRangingState(0); - dwSetReceiveWaitTimeout(dev, TDOA2_RECEIVE_TIMEOUT); +// dwCommitConfiguration(dev); - dwCommitConfiguration(dev); - - rangingOk = false; -} +// rangingOk = false; +// } static bool isRangingOk() { @@ -351,14 +352,14 @@ static void lpsHandleLppShortPacket(const uint8_t srcId, const uint8_t *data, td } } -uwbAlgorithm_t uwbTdoa2TagAlgorithm = { - .init = Initialize, - .onEvent = onEvent, - .isRangingOk = isRangingOk, - .getAnchorPosition = getAnchorPosition, - .getAnchorIdList = getAnchorIdList, - .getActiveAnchorIdList = getActiveAnchorIdList, -}; +// uwbAlgorithm_t uwbTdoa2TagAlgorithm = { +// .init = Initialize, +// .onEvent = onEvent, +// .isRangingOk = isRangingOk, +// .getAnchorPosition = getAnchorPosition, +// .getAnchorIdList = getAnchorIdList, +// .getActiveAnchorIdList = getActiveAnchorIdList, +// }; void lpsTdoa2TagSetOptions(lpsTdoa2AlgoOptions_t* newOptions) { options = newOptions; diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/lpsTdoa3Tag.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/lpsTdoa3Tag.c index 51b0a1038..0b32ecbf7 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/lpsTdoa3Tag.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/lpsTdoa3Tag.c @@ -52,7 +52,7 @@ The implementation must handle #include "tdoaStats.h" #include "estimator.h" -#include "libdw1000.h" +//#include "libdw1000.h" #include "mac.h" #define DEBUG_MODULE "TDOA3" @@ -162,100 +162,101 @@ static void handleLppPacket(const int dataLength, int rangePacketLength, const p } } -static void rxcallback(dwDevice_t *dev) { - tdoaStats_t* stats = &tdoaEngineState.stats; - STATS_CNT_RATE_EVENT(&stats->packetsReceived); - - int dataLength = dwGetDataLength(dev); - packet_t rxPacket; - - dwGetData(dev, (uint8_t*)&rxPacket, dataLength); - const uint8_t anchorId = rxPacket.sourceAddress & 0xff; - - dwTime_t arrival = {.full = 0}; - dwGetReceiveTimestamp(dev, &arrival); - const int64_t rxAn_by_T_in_cl_T = arrival.full; - - const rangePacket3_t* packet = (rangePacket3_t*)rxPacket.payload; - if (packet->header.type == PACKET_TYPE_TDOA3) { - const int64_t txAn_in_cl_An = packet->header.txTimeStamp;; - const uint8_t seqNr = packet->header.seq & 0x7f;; - - tdoaAnchorContext_t anchorCtx; - uint32_t now_ms = T2M(xTaskGetTickCount()); - - tdoaEngineGetAnchorCtxForPacketProcessing(&tdoaEngineState, anchorId, now_ms, &anchorCtx); - int rangeDataLength = updateRemoteData(&anchorCtx, packet); - tdoaEngineProcessPacket(&tdoaEngineState, &anchorCtx, txAn_in_cl_An, rxAn_by_T_in_cl_T); - tdoaStorageSetRxTxData(&anchorCtx, rxAn_by_T_in_cl_T, txAn_in_cl_An, seqNr); - handleLppPacket(dataLength, rangeDataLength, &rxPacket, &anchorCtx); - - rangingOk = true; - } -} - -static void setRadioInReceiveMode(dwDevice_t *dev) { - dwNewReceive(dev); - dwSetDefaults(dev); - dwStartReceive(dev); -} - -static void sendLppShort(dwDevice_t *dev, lpsLppShortPacket_t *packet) -{ - static packet_t txPacket; - dwIdle(dev); - - MAC80215_PACKET_INIT(txPacket, MAC802154_TYPE_DATA); - - txPacket.payload[LPS_TDOA3_TYPE] = LPP_HEADER_SHORT_PACKET; - memcpy(&txPacket.payload[LPS_TDOA3_SEND_LPP_PAYLOAD], packet->data, packet->length); - - txPacket.pan = 0xbccf; - txPacket.sourceAddress = 0xbccf000000000000 | 0xff; - txPacket.destAddress = 0xbccf000000000000 | packet->dest; - - dwNewTransmit(dev); - dwSetDefaults(dev); - dwSetData(dev, (uint8_t*)&txPacket, MAC802154_HEADER_LENGTH+1+packet->length); - - dwStartTransmit(dev); -} - -static bool sendLpp(dwDevice_t *dev) { - bool lppPacketToSend = lpsGetLppShort(&lppPacket); - if (lppPacketToSend) { - sendLppShort(dev, &lppPacket); - return true; - } - - return false; -} - -static uint32_t onEvent(dwDevice_t *dev, uwbEvent_t event) { - switch(event) { - case eventPacketReceived: - rxcallback(dev); - break; - case eventTimeout: - break; - case eventReceiveTimeout: - break; - case eventPacketSent: - // Service packet sent, the radio is back to receive automatically - break; - default: - ASSERT_FAILED(); - } - - if(!sendLpp(dev)) { - setRadioInReceiveMode(dev); - } - - uint32_t now_ms = T2M(xTaskGetTickCount()); - tdoaStatsUpdate(&tdoaEngineState.stats, now_ms); - - return MAX_TIMEOUT; -} +//COMMENTED FIRMWARE +// static void rxcallback(dwDevice_t *dev) { +// tdoaStats_t* stats = &tdoaEngineState.stats; +// STATS_CNT_RATE_EVENT(&stats->packetsReceived); + +// int dataLength = dwGetDataLength(dev); +// packet_t rxPacket; + +// dwGetData(dev, (uint8_t*)&rxPacket, dataLength); +// const uint8_t anchorId = rxPacket.sourceAddress & 0xff; + +// dwTime_t arrival = {.full = 0}; +// dwGetReceiveTimestamp(dev, &arrival); +// const int64_t rxAn_by_T_in_cl_T = arrival.full; + +// const rangePacket3_t* packet = (rangePacket3_t*)rxPacket.payload; +// if (packet->header.type == PACKET_TYPE_TDOA3) { +// const int64_t txAn_in_cl_An = packet->header.txTimeStamp;; +// const uint8_t seqNr = packet->header.seq & 0x7f;; + +// tdoaAnchorContext_t anchorCtx; +// uint32_t now_ms = T2M(xTaskGetTickCount()); + +// tdoaEngineGetAnchorCtxForPacketProcessing(&tdoaEngineState, anchorId, now_ms, &anchorCtx); +// int rangeDataLength = updateRemoteData(&anchorCtx, packet); +// tdoaEngineProcessPacket(&tdoaEngineState, &anchorCtx, txAn_in_cl_An, rxAn_by_T_in_cl_T); +// tdoaStorageSetRxTxData(&anchorCtx, rxAn_by_T_in_cl_T, txAn_in_cl_An, seqNr); +// handleLppPacket(dataLength, rangeDataLength, &rxPacket, &anchorCtx); + +// rangingOk = true; +// } +// } + +// static void setRadioInReceiveMode(dwDevice_t *dev) { +// dwNewReceive(dev); +// dwSetDefaults(dev); +// dwStartReceive(dev); +// } + +// static void sendLppShort(dwDevice_t *dev, lpsLppShortPacket_t *packet) +// { +// static packet_t txPacket; +// dwIdle(dev); + +// MAC80215_PACKET_INIT(txPacket, MAC802154_TYPE_DATA); + +// txPacket.payload[LPS_TDOA3_TYPE] = LPP_HEADER_SHORT_PACKET; +// memcpy(&txPacket.payload[LPS_TDOA3_SEND_LPP_PAYLOAD], packet->data, packet->length); + +// txPacket.pan = 0xbccf; +// txPacket.sourceAddress = 0xbccf000000000000 | 0xff; +// txPacket.destAddress = 0xbccf000000000000 | packet->dest; + +// dwNewTransmit(dev); +// dwSetDefaults(dev); +// dwSetData(dev, (uint8_t*)&txPacket, MAC802154_HEADER_LENGTH+1+packet->length); + +// dwStartTransmit(dev); +// } + +// static bool sendLpp(dwDevice_t *dev) { +// bool lppPacketToSend = lpsGetLppShort(&lppPacket); +// if (lppPacketToSend) { +// sendLppShort(dev, &lppPacket); +// return true; +// } + +// return false; +// } + +// static uint32_t onEvent(dwDevice_t *dev, uwbEvent_t event) { +// switch(event) { +// case eventPacketReceived: +// rxcallback(dev); +// break; +// case eventTimeout: +// break; +// case eventReceiveTimeout: +// break; +// case eventPacketSent: +// // Service packet sent, the radio is back to receive automatically +// break; +// default: +// ASSERT_FAILED(); +// } + +// if(!sendLpp(dev)) { +// setRadioInReceiveMode(dev); +// } + +// uint32_t now_ms = T2M(xTaskGetTickCount()); +// tdoaStatsUpdate(&tdoaEngineState.stats, now_ms); + +// return MAX_TIMEOUT; +// } static void sendTdoaToEstimatorCallback(tdoaMeasurement_t* tdoaMeasurement) { estimatorEnqueueTDOA(tdoaMeasurement); @@ -293,31 +294,33 @@ static uint8_t getActiveAnchorIdList(uint8_t unorderedAnchorList[], const int ma return tdoaStorageGetListOfActiveAnchorIds(tdoaEngineState.anchorInfoArray, unorderedAnchorList, maxListSize, now_ms); } -static void Initialize(dwDevice_t *dev) { - uint32_t now_ms = T2M(xTaskGetTickCount()); - tdoaEngineInit(&tdoaEngineState, now_ms, sendTdoaToEstimatorCallback, LOCODECK_TS_FREQ, TdoaEngineMatchingAlgorithmRandom); +//COMMENTED FIRMWARE +// static void Initialize(dwDevice_t *dev) { +// uint32_t now_ms = T2M(xTaskGetTickCount()); +// tdoaEngineInit(&tdoaEngineState, now_ms, sendTdoaToEstimatorCallback, LOCODECK_TS_FREQ, TdoaEngineMatchingAlgorithmRandom); - #ifdef LPS_2D_POSITION_HEIGHT - DEBUG_PRINT("2D positioning enabled at %f m height\n", LPS_2D_POSITION_HEIGHT); - #endif +// #ifdef LPS_2D_POSITION_HEIGHT +// DEBUG_PRINT("2D positioning enabled at %f m height\n", LPS_2D_POSITION_HEIGHT); +// #endif - dwSetReceiveWaitTimeout(dev, TDOA3_RECEIVE_TIMEOUT); +// dwSetReceiveWaitTimeout(dev, TDOA3_RECEIVE_TIMEOUT); - dwCommitConfiguration(dev); +// dwCommitConfiguration(dev); - rangingOk = false; -} +// rangingOk = false; +// } static bool isRangingOk() { return rangingOk; } -uwbAlgorithm_t uwbTdoa3TagAlgorithm = { - .init = Initialize, - .onEvent = onEvent, - .isRangingOk = isRangingOk, - .getAnchorPosition = getAnchorPosition, - .getAnchorIdList = getAnchorIdList, - .getActiveAnchorIdList = getActiveAnchorIdList, -}; +//COMMENTED FIRMWARE +// uwbAlgorithm_t uwbTdoa3TagAlgorithm = { +// .init = Initialize, +// .onEvent = onEvent, +// .isRangingOk = isRangingOk, +// .getAnchorPosition = getAnchorPosition, +// .getAnchorIdList = getAnchorIdList, +// .getActiveAnchorIdList = getActiveAnchorIdList, +// }; diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/lpsTwrTag.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/lpsTwrTag.c index d99344dcc..bed043dd8 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/lpsTwrTag.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/lpsTwrTag.c @@ -99,10 +99,12 @@ static lpsTwrAlgoOptions_t* options = &defaultOptions; // Outlier rejection #define RANGING_HISTORY_LENGTH 32 #define OUTLIER_TH 4 -NO_DMA_CCM_SAFE_ZERO_INIT static struct { - float32_t history[RANGING_HISTORY_LENGTH]; - size_t ptr; -} rangingStats[LOCODECK_NR_OF_TWR_ANCHORS]; + +//COMMENTED FIRMWARE +// NO_DMA_CCM_SAFE_ZERO_INIT static struct { +// float32_t history[RANGING_HISTORY_LENGTH]; +// size_t ptr; +// } rangingStats[LOCODECK_NR_OF_TWR_ANCHORS]; // Rangin statistics static uint8_t rangingPerSec[LOCODECK_NR_OF_TWR_ANCHORS]; @@ -112,12 +114,13 @@ static uint8_t succededRanging[LOCODECK_NR_OF_TWR_ANCHORS]; static uint8_t failedRanging[LOCODECK_NR_OF_TWR_ANCHORS]; // Timestamps for ranging -static dwTime_t poll_tx; -static dwTime_t poll_rx; -static dwTime_t answer_tx; -static dwTime_t answer_rx; -static dwTime_t final_tx; -static dwTime_t final_rx; +//COMMENTED FIRMWARE +// static dwTime_t poll_tx; +// static dwTime_t poll_rx; +// static dwTime_t answer_tx; +// static dwTime_t answer_rx; +// static dwTime_t final_tx; +// static dwTime_t final_rx; static packet_t txPacket; static volatile uint8_t curr_seq = 0; @@ -130,309 +133,313 @@ static lpsLppShortPacket_t lppShortPacket; // TDMA handling static bool tdmaSynchronized; -static dwTime_t frameStart; +//COMMENTED FIRMWARE +// static dwTime_t frameStart; static bool rangingOk; static void lpsHandleLppShortPacket(const uint8_t srcId, const uint8_t *data); -static void txcallback(dwDevice_t *dev) -{ - dwTime_t departure; - dwGetTransmitTimestamp(dev, &departure); - departure.full += (options->antennaDelay / 2); - - switch (txPacket.payload[0]) { - case LPS_TWR_POLL: - poll_tx = departure; - break; - case LPS_TWR_FINAL: - final_tx = departure; - break; - } -} - - -static uint32_t rxcallback(dwDevice_t *dev) { - dwTime_t arival = { .full=0 }; - int dataLength = dwGetDataLength(dev); - - if (dataLength == 0) return 0; - - packet_t rxPacket; - memset(&rxPacket, 0, MAC802154_HEADER_LENGTH); - - dwGetData(dev, (uint8_t*)&rxPacket, dataLength); - - if (rxPacket.destAddress != options->tagAddress) { - dwNewReceive(dev); - dwSetDefaults(dev); - dwStartReceive(dev); - return MAX_TIMEOUT; - } - - txPacket.destAddress = rxPacket.sourceAddress; - txPacket.sourceAddress = rxPacket.destAddress; - - switch(rxPacket.payload[LPS_TWR_TYPE]) { - // Tag received messages - case LPS_TWR_ANSWER: - if (rxPacket.payload[LPS_TWR_SEQ] != curr_seq) { - return 0; - } - - if (dataLength - MAC802154_HEADER_LENGTH > 3) { - if (rxPacket.payload[LPS_TWR_LPP_HEADER] == LPP_HEADER_SHORT_PACKET) { - int srcId = -1; - - for (int i=0; i<LOCODECK_NR_OF_TWR_ANCHORS; i++) { - if (rxPacket.sourceAddress == options->anchorAddress[i]) { - srcId = i; - break; - } - } - - if (srcId >= 0) { - lpsHandleLppShortPacket(srcId, &rxPacket.payload[LPS_TWR_LPP_TYPE]); - } - } - } - - txPacket.payload[LPS_TWR_TYPE] = LPS_TWR_FINAL; - txPacket.payload[LPS_TWR_SEQ] = rxPacket.payload[LPS_TWR_SEQ]; - - dwGetReceiveTimestamp(dev, &arival); - arival.full -= (options->antennaDelay / 2); - answer_rx = arival; - - dwNewTransmit(dev); - dwSetData(dev, (uint8_t*)&txPacket, MAC802154_HEADER_LENGTH+2); - - dwWaitForResponse(dev, true); - dwStartTransmit(dev); - - break; - case LPS_TWR_REPORT: - { - lpsTwrTagReportPayload_t *report = (lpsTwrTagReportPayload_t *)(rxPacket.payload+2); - double tround1, treply1, treply2, tround2, tprop_ctn, tprop; - - if (rxPacket.payload[LPS_TWR_SEQ] != curr_seq) { - return 0; - } - - memcpy(&poll_rx, &report->pollRx, 5); - memcpy(&answer_tx, &report->answerTx, 5); - memcpy(&final_rx, &report->finalRx, 5); - - tround1 = answer_rx.low32 - poll_tx.low32; - treply1 = answer_tx.low32 - poll_rx.low32; - tround2 = final_rx.low32 - answer_tx.low32; - treply2 = final_tx.low32 - answer_rx.low32; - - tprop_ctn = ((tround1*tround2) - (treply1*treply2)) / (tround1 + tround2 + treply1 + treply2); - - tprop = tprop_ctn / LOCODECK_TS_FREQ; - state.distance[current_anchor] = SPEED_OF_LIGHT * tprop; - state.pressures[current_anchor] = report->asl; - - // Outliers rejection - rangingStats[current_anchor].ptr = (rangingStats[current_anchor].ptr + 1) % RANGING_HISTORY_LENGTH; - float32_t mean; - float32_t stddev; - - arm_std_f32(rangingStats[current_anchor].history, RANGING_HISTORY_LENGTH, &stddev); - arm_mean_f32(rangingStats[current_anchor].history, RANGING_HISTORY_LENGTH, &mean); - float32_t diff = fabsf(mean - state.distance[current_anchor]); - - rangingStats[current_anchor].history[rangingStats[current_anchor].ptr] = state.distance[current_anchor]; - - rangingOk = true; - - if ((options->combinedAnchorPositionOk || options->anchorPosition[current_anchor].timestamp) && - (diff < (OUTLIER_TH*stddev))) { - distanceMeasurement_t dist; - dist.distance = state.distance[current_anchor]; - dist.x = options->anchorPosition[current_anchor].x; - dist.y = options->anchorPosition[current_anchor].y; - dist.z = options->anchorPosition[current_anchor].z; - dist.anchorId = current_anchor; - dist.stdDev = 0.25; - estimatorEnqueueDistance(&dist); - } - - if (options->useTdma && current_anchor == 0) { - // Final packet is sent by us and received by the anchor - // We use it as synchonisation time for TDMA - dwTime_t offset = { .full =final_tx.full - final_rx.full }; - frameStart.full = TDMA_LAST_FRAME(final_rx.full) + offset.full; - tdmaSynchronized = true; - } - - ranging_complete = true; - - return 0; - break; - } - } - return MAX_TIMEOUT; -} - +//COMMENTED FIRMWARE +// static void txcallback(dwDevice_t *dev) +// { +// dwTime_t departure; +// dwGetTransmitTimestamp(dev, &departure); +// departure.full += (options->antennaDelay / 2); + +// switch (txPacket.payload[0]) { +// case LPS_TWR_POLL: +// poll_tx = departure; +// break; +// case LPS_TWR_FINAL: +// final_tx = departure; +// break; +// } +// } + +//COMMENTED FIRMWARE +// static uint32_t rxcallback(dwDevice_t *dev) { +// dwTime_t arival = { .full=0 }; +// int dataLength = dwGetDataLength(dev); + +// if (dataLength == 0) return 0; + +// packet_t rxPacket; +// memset(&rxPacket, 0, MAC802154_HEADER_LENGTH); + +// dwGetData(dev, (uint8_t*)&rxPacket, dataLength); + +// if (rxPacket.destAddress != options->tagAddress) { +// dwNewReceive(dev); +// dwSetDefaults(dev); +// dwStartReceive(dev); +// return MAX_TIMEOUT; +// } + +// txPacket.destAddress = rxPacket.sourceAddress; +// txPacket.sourceAddress = rxPacket.destAddress; + +// switch(rxPacket.payload[LPS_TWR_TYPE]) { +// // Tag received messages +// case LPS_TWR_ANSWER: +// if (rxPacket.payload[LPS_TWR_SEQ] != curr_seq) { +// return 0; +// } + +// if (dataLength - MAC802154_HEADER_LENGTH > 3) { +// if (rxPacket.payload[LPS_TWR_LPP_HEADER] == LPP_HEADER_SHORT_PACKET) { +// int srcId = -1; + +// for (int i=0; i<LOCODECK_NR_OF_TWR_ANCHORS; i++) { +// if (rxPacket.sourceAddress == options->anchorAddress[i]) { +// srcId = i; +// break; +// } +// } + +// if (srcId >= 0) { +// lpsHandleLppShortPacket(srcId, &rxPacket.payload[LPS_TWR_LPP_TYPE]); +// } +// } +// } + +// txPacket.payload[LPS_TWR_TYPE] = LPS_TWR_FINAL; +// txPacket.payload[LPS_TWR_SEQ] = rxPacket.payload[LPS_TWR_SEQ]; + +// dwGetReceiveTimestamp(dev, &arival); +// arival.full -= (options->antennaDelay / 2); +// answer_rx = arival; + +// dwNewTransmit(dev); +// dwSetData(dev, (uint8_t*)&txPacket, MAC802154_HEADER_LENGTH+2); + +// dwWaitForResponse(dev, true); +// dwStartTransmit(dev); + +// break; +// case LPS_TWR_REPORT: +// { +// lpsTwrTagReportPayload_t *report = (lpsTwrTagReportPayload_t *)(rxPacket.payload+2); +// double tround1, treply1, treply2, tround2, tprop_ctn, tprop; + +// if (rxPacket.payload[LPS_TWR_SEQ] != curr_seq) { +// return 0; +// } + +// memcpy(&poll_rx, &report->pollRx, 5); +// memcpy(&answer_tx, &report->answerTx, 5); +// memcpy(&final_rx, &report->finalRx, 5); + +// tround1 = answer_rx.low32 - poll_tx.low32; +// treply1 = answer_tx.low32 - poll_rx.low32; +// tround2 = final_rx.low32 - answer_tx.low32; +// treply2 = final_tx.low32 - answer_rx.low32; + +// tprop_ctn = ((tround1*tround2) - (treply1*treply2)) / (tround1 + tround2 + treply1 + treply2); + +// tprop = tprop_ctn / LOCODECK_TS_FREQ; +// state.distance[current_anchor] = SPEED_OF_LIGHT * tprop; +// state.pressures[current_anchor] = report->asl; + +// // Outliers rejection +// rangingStats[current_anchor].ptr = (rangingStats[current_anchor].ptr + 1) % RANGING_HISTORY_LENGTH; +// float32_t mean; +// float32_t stddev; + +// arm_std_f32(rangingStats[current_anchor].history, RANGING_HISTORY_LENGTH, &stddev); +// arm_mean_f32(rangingStats[current_anchor].history, RANGING_HISTORY_LENGTH, &mean); +// float32_t diff = fabsf(mean - state.distance[current_anchor]); + +// rangingStats[current_anchor].history[rangingStats[current_anchor].ptr] = state.distance[current_anchor]; + +// rangingOk = true; + +// if ((options->combinedAnchorPositionOk || options->anchorPosition[current_anchor].timestamp) && +// (diff < (OUTLIER_TH*stddev))) { +// distanceMeasurement_t dist; +// dist.distance = state.distance[current_anchor]; +// dist.x = options->anchorPosition[current_anchor].x; +// dist.y = options->anchorPosition[current_anchor].y; +// dist.z = options->anchorPosition[current_anchor].z; +// dist.anchorId = current_anchor; +// dist.stdDev = 0.25; +// estimatorEnqueueDistance(&dist); +// } + +// if (options->useTdma && current_anchor == 0) { +// // Final packet is sent by us and received by the anchor +// // We use it as synchonisation time for TDMA +// dwTime_t offset = { .full =final_tx.full - final_rx.full }; +// frameStart.full = TDMA_LAST_FRAME(final_rx.full) + offset.full; +// tdmaSynchronized = true; +// } + +// ranging_complete = true; + +// return 0; +// break; +// } +// } +// return MAX_TIMEOUT; +// } + +//COMMENTED FIRMWARE /* Adjust time for schedule transfer by DW1000 radio. Set 9 LSB to 0 */ -static uint32_t adjustTxRxTime(dwTime_t *time) -{ - uint32_t added = (1<<9) - (time->low32 & ((1<<9)-1)); - time->low32 = (time->low32 & ~((1<<9)-1)) + (1<<9); - return added; -} - -/* Calculate the transmit time for a given timeslot in the current frame */ -static dwTime_t transmitTimeForSlot(int slot) -{ - dwTime_t transmitTime = { .full = 0 }; - // Calculate start of the slot - transmitTime.full = frameStart.full + slot*TDMA_SLOT_LEN; - - // DW1000 can only schedule time with 9 LSB at 0, adjust for it - adjustTxRxTime(&transmitTime); - return transmitTime; -} - -static void initiateRanging(dwDevice_t *dev) -{ - if (!options->useTdma || tdmaSynchronized) { - if (options->useTdma) { - // go to next TDMA frame - frameStart.full += TDMA_FRAME_LEN; - } - - current_anchor ++; - if (current_anchor >= LOCODECK_NR_OF_TWR_ANCHORS) { - current_anchor = 0; - } - } else { - current_anchor = 0; - } - - dwIdle(dev); - - txPacket.payload[LPS_TWR_TYPE] = LPS_TWR_POLL; - txPacket.payload[LPS_TWR_SEQ] = ++curr_seq; - - txPacket.sourceAddress = options->tagAddress; - txPacket.destAddress = options->anchorAddress[current_anchor]; - - dwNewTransmit(dev); - dwSetDefaults(dev); - dwSetData(dev, (uint8_t*)&txPacket, MAC802154_HEADER_LENGTH+2); - - if (options->useTdma && tdmaSynchronized) { - dwTime_t txTime = transmitTimeForSlot(options->tdmaSlot); - dwSetTxRxTime(dev, txTime); - } - - dwWaitForResponse(dev, true); - dwStartTransmit(dev); -} - -static void sendLppShort(dwDevice_t *dev, lpsLppShortPacket_t *packet) -{ - dwIdle(dev); - - txPacket.payload[LPS_TWR_TYPE] = LPS_TWR_LPP_SHORT; - memcpy(&txPacket.payload[LPS_TWR_SEND_LPP_PAYLOAD], packet->data, packet->length); - - txPacket.sourceAddress = options->tagAddress; - txPacket.destAddress = options->anchorAddress[packet->dest]; - - dwNewTransmit(dev); - dwSetDefaults(dev); - dwSetData(dev, (uint8_t*)&txPacket, MAC802154_HEADER_LENGTH+1+packet->length); - - dwWaitForResponse(dev, false); - dwStartTransmit(dev); -} - -static uint32_t twrTagOnEvent(dwDevice_t *dev, uwbEvent_t event) -{ - static uint32_t statisticStartTick = 0; - - if (statisticStartTick == 0) { - statisticStartTick = xTaskGetTickCount(); - } - - switch(event) { - case eventPacketReceived: - return rxcallback(dev); - break; - case eventPacketSent: - txcallback(dev); - - if (lpp_transaction) { - return 0; - } - return MAX_TIMEOUT; - break; - case eventTimeout: // Comes back to timeout after each ranging attempt - { - uint16_t rangingState = locoDeckGetRangingState(); - if (!ranging_complete && !lpp_transaction) { - rangingState &= ~(1<<current_anchor); - if (state.failedRanging[current_anchor] < options->rangingFailedThreshold) { - state.failedRanging[current_anchor] ++; - rangingState |= (1<<current_anchor); - } - - locSrvSendRangeFloat(current_anchor, NAN); - failedRanging[current_anchor]++; - } else { - rangingState |= (1<<current_anchor); - state.failedRanging[current_anchor] = 0; - - locSrvSendRangeFloat(current_anchor, state.distance[current_anchor]); - succededRanging[current_anchor]++; - } - locoDeckSetRangingState(rangingState); - } - - // Handle ranging statistic - if (xTaskGetTickCount() > (statisticStartTick+1000)) { - statisticStartTick = xTaskGetTickCount(); - - for (int i=0; i<LOCODECK_NR_OF_TWR_ANCHORS; i++) { - rangingPerSec[i] = failedRanging[i] + succededRanging[i]; - if (rangingPerSec[i] > 0) { - rangingSuccessRate[i] = 100.0f*(float)succededRanging[i] / (float)rangingPerSec[i]; - } else { - rangingSuccessRate[i] = 0.0f; - } - - failedRanging[i] = 0; - succededRanging[i] = 0; - } - } - - - if (lpsGetLppShort(&lppShortPacket)) { - lpp_transaction = true; - sendLppShort(dev, &lppShortPacket); - } else { - lpp_transaction = false; - ranging_complete = false; - initiateRanging(dev); - } - return MAX_TIMEOUT; - break; - case eventReceiveTimeout: - case eventReceiveFailed: - return 0; - break; - default: - configASSERT(false); - } - - return MAX_TIMEOUT; -} +// static uint32_t adjustTxRxTime(dwTime_t *time) +// { +// uint32_t added = (1<<9) - (time->low32 & ((1<<9)-1)); +// time->low32 = (time->low32 & ~((1<<9)-1)) + (1<<9); +// return added; +// } + +// /* Calculate the transmit time for a given timeslot in the current frame */ +// static dwTime_t transmitTimeForSlot(int slot) +// { +// dwTime_t transmitTime = { .full = 0 }; +// // Calculate start of the slot +// transmitTime.full = frameStart.full + slot*TDMA_SLOT_LEN; + +// // DW1000 can only schedule time with 9 LSB at 0, adjust for it +// adjustTxRxTime(&transmitTime); +// return transmitTime; +// } + +//COMMENTED FIRMWARE +// static void initiateRanging(dwDevice_t *dev) +// { +// if (!options->useTdma || tdmaSynchronized) { +// if (options->useTdma) { +// // go to next TDMA frame +// frameStart.full += TDMA_FRAME_LEN; +// } + +// current_anchor ++; +// if (current_anchor >= LOCODECK_NR_OF_TWR_ANCHORS) { +// current_anchor = 0; +// } +// } else { +// current_anchor = 0; +// } + +// dwIdle(dev); + +// txPacket.payload[LPS_TWR_TYPE] = LPS_TWR_POLL; +// txPacket.payload[LPS_TWR_SEQ] = ++curr_seq; + +// txPacket.sourceAddress = options->tagAddress; +// txPacket.destAddress = options->anchorAddress[current_anchor]; + +// dwNewTransmit(dev); +// dwSetDefaults(dev); +// dwSetData(dev, (uint8_t*)&txPacket, MAC802154_HEADER_LENGTH+2); + +// if (options->useTdma && tdmaSynchronized) { +// dwTime_t txTime = transmitTimeForSlot(options->tdmaSlot); +// dwSetTxRxTime(dev, txTime); +// } + +// dwWaitForResponse(dev, true); +// dwStartTransmit(dev); +// } + +// static void sendLppShort(dwDevice_t *dev, lpsLppShortPacket_t *packet) +// { +// dwIdle(dev); + +// txPacket.payload[LPS_TWR_TYPE] = LPS_TWR_LPP_SHORT; +// memcpy(&txPacket.payload[LPS_TWR_SEND_LPP_PAYLOAD], packet->data, packet->length); + +// txPacket.sourceAddress = options->tagAddress; +// txPacket.destAddress = options->anchorAddress[packet->dest]; + +// dwNewTransmit(dev); +// dwSetDefaults(dev); +// dwSetData(dev, (uint8_t*)&txPacket, MAC802154_HEADER_LENGTH+1+packet->length); + +// dwWaitForResponse(dev, false); +// dwStartTransmit(dev); +// } + +// static uint32_t twrTagOnEvent(dwDevice_t *dev, uwbEvent_t event) +// { +// static uint32_t statisticStartTick = 0; + +// if (statisticStartTick == 0) { +// statisticStartTick = xTaskGetTickCount(); +// } + +// switch(event) { +// case eventPacketReceived: +// return rxcallback(dev); +// break; +// case eventPacketSent: +// txcallback(dev); + +// if (lpp_transaction) { +// return 0; +// } +// return MAX_TIMEOUT; +// break; +// case eventTimeout: // Comes back to timeout after each ranging attempt +// { +// uint16_t rangingState = locoDeckGetRangingState(); +// if (!ranging_complete && !lpp_transaction) { +// rangingState &= ~(1<<current_anchor); +// if (state.failedRanging[current_anchor] < options->rangingFailedThreshold) { +// state.failedRanging[current_anchor] ++; +// rangingState |= (1<<current_anchor); +// } + +// locSrvSendRangeFloat(current_anchor, NAN); +// failedRanging[current_anchor]++; +// } else { +// rangingState |= (1<<current_anchor); +// state.failedRanging[current_anchor] = 0; + +// locSrvSendRangeFloat(current_anchor, state.distance[current_anchor]); +// succededRanging[current_anchor]++; +// } +// locoDeckSetRangingState(rangingState); +// } + +// // Handle ranging statistic +// if (xTaskGetTickCount() > (statisticStartTick+1000)) { +// statisticStartTick = xTaskGetTickCount(); + +// for (int i=0; i<LOCODECK_NR_OF_TWR_ANCHORS; i++) { +// rangingPerSec[i] = failedRanging[i] + succededRanging[i]; +// if (rangingPerSec[i] > 0) { +// rangingSuccessRate[i] = 100.0f*(float)succededRanging[i] / (float)rangingPerSec[i]; +// } else { +// rangingSuccessRate[i] = 0.0f; +// } + +// failedRanging[i] = 0; +// succededRanging[i] = 0; +// } +// } + + +// if (lpsGetLppShort(&lppShortPacket)) { +// lpp_transaction = true; +// sendLppShort(dev, &lppShortPacket); +// } else { +// lpp_transaction = false; +// ranging_complete = false; +// initiateRanging(dev); +// } +// return MAX_TIMEOUT; +// break; +// case eventReceiveTimeout: +// case eventReceiveFailed: +// return 0; +// break; +// default: +// configASSERT(false); +// } + +// return MAX_TIMEOUT; +// } // Loco Posisioning Protocol (LPP) handling static void lpsHandleLppShortPacket(const uint8_t srcId, const uint8_t *data) @@ -463,41 +470,41 @@ static void updateTagTdmaSlot(lpsTwrAlgoOptions_t * options) options->tagAddress += options->tdmaSlot; } +//COMMENTED FIRMWARE +// static void twrTagInit(dwDevice_t *dev) +// { +// updateTagTdmaSlot(options); -static void twrTagInit(dwDevice_t *dev) -{ - updateTagTdmaSlot(options); - - // Initialize the packet in the TX buffer - memset(&txPacket, 0, sizeof(txPacket)); - MAC80215_PACKET_INIT(txPacket, MAC802154_TYPE_DATA); - txPacket.pan = 0xbccf; +// // Initialize the packet in the TX buffer +// memset(&txPacket, 0, sizeof(txPacket)); +// MAC80215_PACKET_INIT(txPacket, MAC802154_TYPE_DATA); +// txPacket.pan = 0xbccf; - memset(&poll_tx, 0, sizeof(poll_tx)); - memset(&poll_rx, 0, sizeof(poll_rx)); - memset(&answer_tx, 0, sizeof(answer_tx)); - memset(&answer_rx, 0, sizeof(answer_rx)); - memset(&final_tx, 0, sizeof(final_tx)); - memset(&final_rx, 0, sizeof(final_rx)); +// memset(&poll_tx, 0, sizeof(poll_tx)); +// memset(&poll_rx, 0, sizeof(poll_rx)); +// memset(&answer_tx, 0, sizeof(answer_tx)); +// memset(&answer_rx, 0, sizeof(answer_rx)); +// memset(&final_tx, 0, sizeof(final_tx)); +// memset(&final_rx, 0, sizeof(final_rx)); - curr_seq = 0; - current_anchor = 0; +// curr_seq = 0; +// current_anchor = 0; - locoDeckSetRangingState(0); - ranging_complete = false; +// locoDeckSetRangingState(0); +// ranging_complete = false; - tdmaSynchronized = false; +// tdmaSynchronized = false; - memset(state.distance, 0, sizeof(state.distance)); - memset(state.pressures, 0, sizeof(state.pressures)); - memset(state.failedRanging, 0, sizeof(state.failedRanging)); +// memset(state.distance, 0, sizeof(state.distance)); +// memset(state.pressures, 0, sizeof(state.pressures)); +// memset(state.failedRanging, 0, sizeof(state.failedRanging)); - dwSetReceiveWaitTimeout(dev, TWR_RECEIVE_TIMEOUT); +// dwSetReceiveWaitTimeout(dev, TWR_RECEIVE_TIMEOUT); - dwCommitConfiguration(dev); +// dwCommitConfiguration(dev); - rangingOk = false; -} +// rangingOk = false; +// } static bool isRangingOk() { @@ -542,14 +549,15 @@ static uint8_t getActiveAnchorIdList(uint8_t unorderedAnchorList[], const int ma return count; } -uwbAlgorithm_t uwbTwrTagAlgorithm = { - .init = twrTagInit, - .onEvent = twrTagOnEvent, - .isRangingOk = isRangingOk, - .getAnchorPosition = getAnchorPosition, - .getAnchorIdList = getAnchorIdList, - .getActiveAnchorIdList = getActiveAnchorIdList, -}; +//COMMENTED FIRMWARE +// uwbAlgorithm_t uwbTwrTagAlgorithm = { +// .init = twrTagInit, +// .onEvent = twrTagOnEvent, +// .isRangingOk = isRangingOk, +// .getAnchorPosition = getAnchorPosition, +// .getAnchorIdList = getAnchorIdList, +// .getActiveAnchorIdList = getActiveAnchorIdList, +// }; /** * Log group for Two Way Ranging data diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/test/exptest.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/test/exptest.c index 52a3c7d01..f29fa51c4 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/test/exptest.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/test/exptest.c @@ -81,21 +81,23 @@ typedef struct _etGpio static EtGpio etGpioIn[ET_NBR_PINS] = { - {ET_GPIO_PORT_TX1, ET_GPIO_PIN_TX1, "TX1"}, - {ET_GPIO_PORT_RX1, ET_GPIO_PIN_RX1, "RX1"}, - {ET_GPIO_PORT_TX2, ET_GPIO_PIN_TX2, "TX2"}, - {ET_GPIO_PORT_RX2, ET_GPIO_PIN_RX2, "RX2"}, - {ET_GPIO_PORT_SCK, ET_GPIO_PIN_SCK, "SCK"}, - {ET_GPIO_PORT_MOSI, ET_GPIO_PIN_MOSI, "MOSI"}, - {ET_GPIO_PORT_MISO, ET_GPIO_PIN_MISO, "MISO"}, - {ET_GPIO_PORT_IO1, ET_GPIO_PIN_IO1, "IO1"}, - {ET_GPIO_PORT_IO2, ET_GPIO_PIN_IO2, "IO2"}, - {ET_GPIO_PORT_IO3, ET_GPIO_PIN_IO3, "IO3"}, - {ET_GPIO_PORT_IO4, ET_GPIO_PIN_IO4, "IO4"} + //COMMENTED FIRMWARE + // {ET_GPIO_PORT_TX1, ET_GPIO_PIN_TX1, "TX1"}, + // {ET_GPIO_PORT_RX1, ET_GPIO_PIN_RX1, "RX1"}, + // {ET_GPIO_PORT_TX2, ET_GPIO_PIN_TX2, "TX2"}, + // {ET_GPIO_PORT_RX2, ET_GPIO_PIN_RX2, "RX2"}, + // {ET_GPIO_PORT_SCK, ET_GPIO_PIN_SCK, "SCK"}, + // {ET_GPIO_PORT_MOSI, ET_GPIO_PIN_MOSI, "MOSI"}, + // {ET_GPIO_PORT_MISO, ET_GPIO_PIN_MISO, "MISO"}, + // {ET_GPIO_PORT_IO1, ET_GPIO_PIN_IO1, "IO1"}, + // {ET_GPIO_PORT_IO2, ET_GPIO_PIN_IO2, "IO2"}, + // {ET_GPIO_PORT_IO3, ET_GPIO_PIN_IO3, "IO3"}, + // {ET_GPIO_PORT_IO4, ET_GPIO_PIN_IO4, "IO4"} }; -static EtGpio etGpioSDA = {ET_GPIO_PORT_SDA, ET_GPIO_PIN_SDA, "SDA"}; -static EtGpio etGpioSCL = {ET_GPIO_PORT_SCL, ET_GPIO_PIN_SCL, "SCL"}; +//COMMENTED FIRMWARE +// static EtGpio etGpioSDA = {ET_GPIO_PORT_SDA, ET_GPIO_PIN_SDA, "SDA"}; +// static EtGpio etGpioSCL = {ET_GPIO_PORT_SCL, ET_GPIO_PIN_SCL, "SCL"}; static bool isInit; @@ -107,76 +109,77 @@ static bool exptestRun(void) int i; volatile int delay; bool status = true; - GPIO_InitTypeDef GPIO_InitStructure; - GpioRegBuf gpioSaved; - - isInit = true; - - status &= sensorsManufacturingTest(); - - - // Enable GPIOs - RCC_AHB1PeriphClockCmd(ET_GPIO_PERIF, ENABLE); - - decktestSaveGPIOStatesABC(&gpioSaved); - - for (i = 0; i < ET_NBR_PINS; i++) - { - //Initialize the pins as inputs - GPIO_InitStructure.GPIO_Pin = etGpioIn[i].pin; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; - GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; - GPIO_Init(etGpioIn[i].port, &GPIO_InitStructure); - } - - for (i = 0; i < ET_NBR_PINS && status; i++) - { - // Configure pin as output to poke others - GPIO_InitStructure.GPIO_Pin = etGpioIn[i].pin; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; - GPIO_Init(etGpioIn[i].port, &GPIO_InitStructure); - - // Test high - GPIO_SetBits(etGpioIn[i].port, etGpioIn[i].pin); - for (delay = 0; delay < 1000; delay++); - if (!exptestTestAllPins(1)) - { - status = false; - } - - // Test low - GPIO_ResetBits(etGpioIn[i].port, etGpioIn[i].pin); - for (delay = 0; delay < 1000; delay++); - if (!exptestTestAllPins(0)) - { - status = false; - } - - // Restore - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN; - GPIO_Init(etGpioIn[i].port, &GPIO_InitStructure); - } - - decktestRestoreGPIOStatesABC(&gpioSaved); - - if (status) - { - // Configure SDA & SCL to turn on OK leds - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; - GPIO_InitStructure.GPIO_Pin = etGpioSDA.pin; - GPIO_Init(etGpioSDA.port, &GPIO_InitStructure); - GPIO_InitStructure.GPIO_Pin = etGpioSCL.pin; - GPIO_Init(etGpioSCL.port, &GPIO_InitStructure); - // Turn on OK LEDs. - GPIO_ResetBits(etGpioSDA.port, etGpioSDA.pin); - GPIO_ResetBits(etGpioSCL.port, etGpioSCL.pin); - } + //COMMENTED FIRMWARE + // GPIO_InitTypeDef GPIO_InitStructure; + // GpioRegBuf gpioSaved; + + // isInit = true; + + // status &= sensorsManufacturingTest(); + + + // // Enable GPIOs + // RCC_AHB1PeriphClockCmd(ET_GPIO_PERIF, ENABLE); + + // decktestSaveGPIOStatesABC(&gpioSaved); + + // for (i = 0; i < ET_NBR_PINS; i++) + // { + // //Initialize the pins as inputs + // GPIO_InitStructure.GPIO_Pin = etGpioIn[i].pin; + // GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN; + // GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + // GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; + // GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; + // GPIO_Init(etGpioIn[i].port, &GPIO_InitStructure); + // } + + // for (i = 0; i < ET_NBR_PINS && status; i++) + // { + // // Configure pin as output to poke others + // GPIO_InitStructure.GPIO_Pin = etGpioIn[i].pin; + // GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; + // GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + // GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; + // GPIO_Init(etGpioIn[i].port, &GPIO_InitStructure); + + // // Test high + // GPIO_SetBits(etGpioIn[i].port, etGpioIn[i].pin); + // for (delay = 0; delay < 1000; delay++); + // if (!exptestTestAllPins(1)) + // { + // status = false; + // } + + // // Test low + // GPIO_ResetBits(etGpioIn[i].port, etGpioIn[i].pin); + // for (delay = 0; delay < 1000; delay++); + // if (!exptestTestAllPins(0)) + // { + // status = false; + // } + + // // Restore + // GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN; + // GPIO_Init(etGpioIn[i].port, &GPIO_InitStructure); + // } + + // decktestRestoreGPIOStatesABC(&gpioSaved); + + // if (status) + // { + // // Configure SDA & SCL to turn on OK leds + // GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; + // GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + // GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; + // GPIO_InitStructure.GPIO_Pin = etGpioSDA.pin; + // GPIO_Init(etGpioSDA.port, &GPIO_InitStructure); + // GPIO_InitStructure.GPIO_Pin = etGpioSCL.pin; + // GPIO_Init(etGpioSCL.port, &GPIO_InitStructure); + // // Turn on OK LEDs. + // GPIO_ResetBits(etGpioSDA.port, etGpioSDA.pin); + // GPIO_ResetBits(etGpioSCL.port, etGpioSCL.pin); + // } return status; } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/test/exptestBolt.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/test/exptestBolt.c index 9f5d24c27..b1a26cbd8 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/test/exptestBolt.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/test/exptestBolt.c @@ -56,7 +56,8 @@ #define ET_GPIO_PIN_MISO GPIO_Pin_7 #define ET_GPIO_PORT_SDA GPIOB -#define ET_GPIO_PIN_SDA GPIO_Pin_7 +//COMMENTED FIRMWARE +// #define ET_GPIO_PIN_SDA GPIO_Pin_7 #define ET_GPIO_PORT_SCL GPIOB #define ET_GPIO_PIN_SCL GPIO_Pin_6 @@ -100,33 +101,36 @@ typedef struct _etGpio static EtGpio etGpioIn[ET_NBR_PINS] = { - {ET_GPIO_PORT_TX1, ET_GPIO_PIN_TX1, "TX1"}, - {ET_GPIO_PORT_RX1, ET_GPIO_PIN_RX1, "RX1"}, - {ET_GPIO_PORT_TX2, ET_GPIO_PIN_TX2, "TX2"}, - {ET_GPIO_PORT_RX2, ET_GPIO_PIN_RX2, "RX2"}, - {ET_GPIO_PORT_SCK, ET_GPIO_PIN_SCK, "SCK"}, - {ET_GPIO_PORT_MOSI, ET_GPIO_PIN_MOSI, "MOSI"}, - {ET_GPIO_PORT_MISO, ET_GPIO_PIN_MISO, "MISO"}, - {ET_GPIO_PORT_IO1, ET_GPIO_PIN_IO1, "IO1"}, - {ET_GPIO_PORT_IO2, ET_GPIO_PIN_IO2, "IO2"}, - {ET_GPIO_PORT_IO3, ET_GPIO_PIN_IO3, "IO3"}, - {ET_GPIO_PORT_IO4, ET_GPIO_PIN_IO4, "IO4"} + //COMMENTED FIRMWARE + // {ET_GPIO_PORT_TX1, ET_GPIO_PIN_TX1, "TX1"}, + // {ET_GPIO_PORT_RX1, ET_GPIO_PIN_RX1, "RX1"}, + // {ET_GPIO_PORT_TX2, ET_GPIO_PIN_TX2, "TX2"}, + // {ET_GPIO_PORT_RX2, ET_GPIO_PIN_RX2, "RX2"}, + // {ET_GPIO_PORT_SCK, ET_GPIO_PIN_SCK, "SCK"}, + // {ET_GPIO_PORT_MOSI, ET_GPIO_PIN_MOSI, "MOSI"}, + // {ET_GPIO_PORT_MISO, ET_GPIO_PIN_MISO, "MISO"}, + // {ET_GPIO_PORT_IO1, ET_GPIO_PIN_IO1, "IO1"}, + // {ET_GPIO_PORT_IO2, ET_GPIO_PIN_IO2, "IO2"}, + // {ET_GPIO_PORT_IO3, ET_GPIO_PIN_IO3, "IO3"}, + // {ET_GPIO_PORT_IO4, ET_GPIO_PIN_IO4, "IO4"} }; static EtGpio etMotorGpio[ET_NBR_MOTOR_PINS] = { - {ET_GPIO_PORT_M1, ET_GPIO_PIN_M1, "M1"}, - {ET_GPIO_PORT_M2, ET_GPIO_PIN_M2, "M2"}, - {ET_GPIO_PORT_M3, ET_GPIO_PIN_M3, "M3"}, - {ET_GPIO_PORT_M4, ET_GPIO_PIN_M4, "M4"}, - {ET_GPIO_PORT_M1_OR, ET_GPIO_PIN_M1_OR, "M1_OR"}, - {ET_GPIO_PORT_M2_OR, ET_GPIO_PIN_M2_OR, "M2_OR"}, - {ET_GPIO_PORT_M3_OR, ET_GPIO_PIN_M3_OR, "M3_OR"}, - {ET_GPIO_PORT_M4_OR, ET_GPIO_PIN_M4_OR, "M4_OR"} + //COMMENTED FIRMWARE + // {ET_GPIO_PORT_M1, ET_GPIO_PIN_M1, "M1"}, + // {ET_GPIO_PORT_M2, ET_GPIO_PIN_M2, "M2"}, + // {ET_GPIO_PORT_M3, ET_GPIO_PIN_M3, "M3"}, + // {ET_GPIO_PORT_M4, ET_GPIO_PIN_M4, "M4"}, + // {ET_GPIO_PORT_M1_OR, ET_GPIO_PIN_M1_OR, "M1_OR"}, + // {ET_GPIO_PORT_M2_OR, ET_GPIO_PIN_M2_OR, "M2_OR"}, + // {ET_GPIO_PORT_M3_OR, ET_GPIO_PIN_M3_OR, "M3_OR"}, + // {ET_GPIO_PORT_M4_OR, ET_GPIO_PIN_M4_OR, "M4_OR"} }; -static EtGpio etGpioSDA = {ET_GPIO_PORT_SDA, ET_GPIO_PIN_SDA, "SDA"}; -static EtGpio etGpioSCL = {ET_GPIO_PORT_SCL, ET_GPIO_PIN_SCL, "SCL"}; +//COMMENTED FIRMWARE +// static EtGpio etGpioSDA = {ET_GPIO_PORT_SDA, ET_GPIO_PIN_SDA, "SDA"}; +// static EtGpio etGpioSCL = {ET_GPIO_PORT_SCL, ET_GPIO_PIN_SCL, "SCL"}; static bool isInit; @@ -135,121 +139,122 @@ static bool exptestTestPin(EtGpio *etPin, bool test); static bool exptestRun(void) { + //COMMENTED FIRMWARE int i; volatile int delay; bool status = true; - GPIO_InitTypeDef GPIO_InitStructure; - GpioRegBuf gpioSaved; - - isInit = true; - - status &= sensorsManufacturingTest(); - - - // Enable GPIOs - RCC_AHB1PeriphClockCmd(ET_GPIO_PERIF, ENABLE); - - decktestSaveGPIOStatesABC(&gpioSaved); - - for (i = 0; i < ET_NBR_PINS; i++) - { - //Initialize the pins as inputs - GPIO_InitStructure.GPIO_Pin = etGpioIn[i].pin; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; - GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; - GPIO_Init(etGpioIn[i].port, &GPIO_InitStructure); - } - - for (i = 0; i < ET_NBR_PINS && status; i++) - { - // Configure pin as output to poke others - GPIO_InitStructure.GPIO_Pin = etGpioIn[i].pin; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; - GPIO_Init(etGpioIn[i].port, &GPIO_InitStructure); - - // Test high - GPIO_SetBits(etGpioIn[i].port, etGpioIn[i].pin); - for (delay = 0; delay < 1000; delay++); - if (!exptestTestAllPins(1)) - { - status = false; - } - - // Test low - GPIO_ResetBits(etGpioIn[i].port, etGpioIn[i].pin); - for (delay = 0; delay < 1000; delay++); - if (!exptestTestAllPins(0)) - { - status = false; - } - - // Restore - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN; - GPIO_Init(etGpioIn[i].port, &GPIO_InitStructure); - } - - // Do Bolt specific tests. Test motor signals - // Initialize the Motor signal pins as inputs - for (i = 0; i < ET_NBR_MOTOR_PINS; i++) - { - //Initialize the pins as inputs - GPIO_InitStructure.GPIO_Pin = etMotorGpio[i].pin; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; - GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; - GPIO_Init(etMotorGpio[i].port, &GPIO_InitStructure); - } - - for (delay = 0; delay < 10000; delay++); - - for (i = 0; i < ET_NBR_SIG_PINS && status; i++) - { - if (!exptestTestPin(&etMotorGpio[i], 1)) - { - status = false; - } - } - - for (i = ET_NBR_SIG_PINS; i < ET_NBR_MOTOR_PINS && status; i++) - { - // Initialize the mosfet pins as outputs. - GPIO_InitStructure.GPIO_Pin = etMotorGpio[i].pin; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; - GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; - GPIO_Init(etMotorGpio[i].port, &GPIO_InitStructure); - // Set high to enable mosfet to pull low - GPIO_SetBits(etMotorGpio[i].port, etMotorGpio[i].pin); - - for (delay = 0; delay < 10000; delay++); - if (!exptestTestPin(&etMotorGpio[i-ET_NBR_SIG_PINS], 0)) - { - status = false; - } - } - - //decktestRestoreGPIOStatesABC(&gpioSaved); - - if (status) - { - // Configure SDA & SCL to turn on OK leds - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; - GPIO_InitStructure.GPIO_Pin = etGpioSDA.pin; - GPIO_Init(etGpioSDA.port, &GPIO_InitStructure); - GPIO_InitStructure.GPIO_Pin = etGpioSCL.pin; - GPIO_Init(etGpioSCL.port, &GPIO_InitStructure); - // Turn on OK LEDs. - GPIO_ResetBits(etGpioSDA.port, etGpioSDA.pin); - GPIO_ResetBits(etGpioSCL.port, etGpioSCL.pin); - } + // GPIO_InitTypeDef GPIO_InitStructure; + // GpioRegBuf gpioSaved; + + // isInit = true; + + // status &= sensorsManufacturingTest(); + + + // // Enable GPIOs + // RCC_AHB1PeriphClockCmd(ET_GPIO_PERIF, ENABLE); + + // decktestSaveGPIOStatesABC(&gpioSaved); + + // for (i = 0; i < ET_NBR_PINS; i++) + // { + // //Initialize the pins as inputs + // GPIO_InitStructure.GPIO_Pin = etGpioIn[i].pin; + // GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN; + // GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + // GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; + // GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; + // GPIO_Init(etGpioIn[i].port, &GPIO_InitStructure); + // } + + // for (i = 0; i < ET_NBR_PINS && status; i++) + // { + // // Configure pin as output to poke others + // GPIO_InitStructure.GPIO_Pin = etGpioIn[i].pin; + // GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; + // GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + // GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; + // GPIO_Init(etGpioIn[i].port, &GPIO_InitStructure); + + // // Test high + // GPIO_SetBits(etGpioIn[i].port, etGpioIn[i].pin); + // for (delay = 0; delay < 1000; delay++); + // if (!exptestTestAllPins(1)) + // { + // status = false; + // } + + // // Test low + // GPIO_ResetBits(etGpioIn[i].port, etGpioIn[i].pin); + // for (delay = 0; delay < 1000; delay++); + // if (!exptestTestAllPins(0)) + // { + // status = false; + // } + + // // Restore + // GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN; + // GPIO_Init(etGpioIn[i].port, &GPIO_InitStructure); + // } + + // // Do Bolt specific tests. Test motor signals + // // Initialize the Motor signal pins as inputs + // for (i = 0; i < ET_NBR_MOTOR_PINS; i++) + // { + // //Initialize the pins as inputs + // GPIO_InitStructure.GPIO_Pin = etMotorGpio[i].pin; + // GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN; + // GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + // GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; + // GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; + // GPIO_Init(etMotorGpio[i].port, &GPIO_InitStructure); + // } + + // for (delay = 0; delay < 10000; delay++); + + // for (i = 0; i < ET_NBR_SIG_PINS && status; i++) + // { + // if (!exptestTestPin(&etMotorGpio[i], 1)) + // { + // status = false; + // } + // } + + // for (i = ET_NBR_SIG_PINS; i < ET_NBR_MOTOR_PINS && status; i++) + // { + // // Initialize the mosfet pins as outputs. + // GPIO_InitStructure.GPIO_Pin = etMotorGpio[i].pin; + // GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; + // GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + // GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; + // GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; + // GPIO_Init(etMotorGpio[i].port, &GPIO_InitStructure); + // // Set high to enable mosfet to pull low + // GPIO_SetBits(etMotorGpio[i].port, etMotorGpio[i].pin); + + // for (delay = 0; delay < 10000; delay++); + // if (!exptestTestPin(&etMotorGpio[i-ET_NBR_SIG_PINS], 0)) + // { + // status = false; + // } + // } + + // //decktestRestoreGPIOStatesABC(&gpioSaved); + + // if (status) + // { + // // Configure SDA & SCL to turn on OK leds + // GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; + // GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + // GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; + // GPIO_InitStructure.GPIO_Pin = etGpioSDA.pin; + // GPIO_Init(etGpioSDA.port, &GPIO_InitStructure); + // GPIO_InitStructure.GPIO_Pin = etGpioSCL.pin; + // GPIO_Init(etGpioSCL.port, &GPIO_InitStructure); + // // Turn on OK LEDs. + // GPIO_ResetBits(etGpioSDA.port, etGpioSDA.pin); + // GPIO_ResetBits(etGpioSCL.port, etGpioSCL.pin); + // } return status; } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/test/exptestRR.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/test/exptestRR.c index 1714733d7..5a3022cce 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/test/exptestRR.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/drivers/src/test/exptestRR.c @@ -67,15 +67,17 @@ typedef struct _etGpio static EtGpio etRRGpioIn[ET_NBR_PINS] = { - {ET_GPIO_PORT_TX2, ET_GPIO_PIN_TX2, "TX2"}, - {ET_GPIO_PORT_RX2, ET_GPIO_PIN_RX2, "RX2"}, - {ET_GPIO_PORT_IO2, ET_GPIO_PIN_IO2, "IO2"}, - {ET_GPIO_PORT_IO3, ET_GPIO_PIN_IO3, "IO3"}, - {ET_GPIO_PORT_IO4, ET_GPIO_PIN_IO4, "IO4"} + //COMMENTED FIRMWARE + // {ET_GPIO_PORT_TX2, ET_GPIO_PIN_TX2, "TX2"}, + // {ET_GPIO_PORT_RX2, ET_GPIO_PIN_RX2, "RX2"}, + // {ET_GPIO_PORT_IO2, ET_GPIO_PIN_IO2, "IO2"}, + // {ET_GPIO_PORT_IO3, ET_GPIO_PIN_IO3, "IO3"}, + // {ET_GPIO_PORT_IO4, ET_GPIO_PIN_IO4, "IO4"} }; -static EtGpio etRRGpioSDA = {ET_GPIO_PORT_SDA, ET_GPIO_PIN_SDA, "SDA"}; -static EtGpio etRRGpioSCL = {ET_GPIO_PORT_SCL, ET_GPIO_PIN_SCL, "SCL"}; +//COMMENTED FIRMWARE +// static EtGpio etRRGpioSDA = {ET_GPIO_PORT_SDA, ET_GPIO_PIN_SDA, "SDA"}; +// static EtGpio etRRGpioSCL = {ET_GPIO_PORT_SCL, ET_GPIO_PIN_SCL, "SCL"}; static bool isInit; @@ -84,79 +86,80 @@ static bool exptestRRTestPin(EtGpio *etPin, bool test); static bool exptestRRRun(void) { + //COMMENTED FIRMWARE int i; volatile int delay; bool status = true; - GPIO_InitTypeDef GPIO_InitStructure; - GpioRegBuf gpioSaved; - - isInit = true; - - status &= sensorsManufacturingTest(); - - - // Enable GPIOs - RCC_AHB1PeriphClockCmd(ET_GPIO_PERIF, ENABLE); - - decktestSaveGPIOStatesABC(&gpioSaved); - - for (i = 0; i < ET_NBR_PINS; i++) - { - //Initialize the pins as inputs - GPIO_InitStructure.GPIO_Pin = etRRGpioIn[i].pin; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; - GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; - GPIO_Init(etRRGpioIn[i].port, &GPIO_InitStructure); - } - - for (i = 0; i < ET_NBR_PINS && status; i++) - { - // Configure pin as output to poke others - GPIO_InitStructure.GPIO_Pin = etRRGpioIn[i].pin; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; - GPIO_Init(etRRGpioIn[i].port, &GPIO_InitStructure); - - // Test high - GPIO_SetBits(etRRGpioIn[i].port, etRRGpioIn[i].pin); - for (delay = 0; delay < 1000; delay++); - if (!exptestRRTestAllPins(1)) - { - status = false; - } - - // Test low - GPIO_ResetBits(etRRGpioIn[i].port, etRRGpioIn[i].pin); - for (delay = 0; delay < 1000; delay++); - if (!exptestRRTestAllPins(0)) - { - status = false; - } - - // Restore - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN; - GPIO_Init(etRRGpioIn[i].port, &GPIO_InitStructure); - } - - decktestRestoreGPIOStatesABC(&gpioSaved); - - if (status) - { - // Configure SDA & SCL to turn on OK leds - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; - GPIO_InitStructure.GPIO_Pin = etRRGpioSDA.pin; - GPIO_Init(etRRGpioSDA.port, &GPIO_InitStructure); - GPIO_InitStructure.GPIO_Pin = etRRGpioSCL.pin; - GPIO_Init(etRRGpioSCL.port, &GPIO_InitStructure); - // Turn on OK LEDs. - GPIO_ResetBits(etRRGpioSDA.port, etRRGpioSDA.pin); - GPIO_ResetBits(etRRGpioSCL.port, etRRGpioSCL.pin); - } + // GPIO_InitTypeDef GPIO_InitStructure; + // GpioRegBuf gpioSaved; + + // isInit = true; + + // status &= sensorsManufacturingTest(); + + + // // Enable GPIOs + // RCC_AHB1PeriphClockCmd(ET_GPIO_PERIF, ENABLE); + + // decktestSaveGPIOStatesABC(&gpioSaved); + + // for (i = 0; i < ET_NBR_PINS; i++) + // { + // //Initialize the pins as inputs + // GPIO_InitStructure.GPIO_Pin = etRRGpioIn[i].pin; + // GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN; + // GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + // GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; + // GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; + // GPIO_Init(etRRGpioIn[i].port, &GPIO_InitStructure); + // } + + // for (i = 0; i < ET_NBR_PINS && status; i++) + // { + // // Configure pin as output to poke others + // GPIO_InitStructure.GPIO_Pin = etRRGpioIn[i].pin; + // GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; + // GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + // GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; + // GPIO_Init(etRRGpioIn[i].port, &GPIO_InitStructure); + + // // Test high + // GPIO_SetBits(etRRGpioIn[i].port, etRRGpioIn[i].pin); + // for (delay = 0; delay < 1000; delay++); + // if (!exptestRRTestAllPins(1)) + // { + // status = false; + // } + + // // Test low + // GPIO_ResetBits(etRRGpioIn[i].port, etRRGpioIn[i].pin); + // for (delay = 0; delay < 1000; delay++); + // if (!exptestRRTestAllPins(0)) + // { + // status = false; + // } + + // // Restore + // GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN; + // GPIO_Init(etRRGpioIn[i].port, &GPIO_InitStructure); + // } + + // decktestRestoreGPIOStatesABC(&gpioSaved); + + // if (status) + // { + // // Configure SDA & SCL to turn on OK leds + // GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; + // GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + // GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed; + // GPIO_InitStructure.GPIO_Pin = etRRGpioSDA.pin; + // GPIO_Init(etRRGpioSDA.port, &GPIO_InitStructure); + // GPIO_InitStructure.GPIO_Pin = etRRGpioSCL.pin; + // GPIO_Init(etRRGpioSCL.port, &GPIO_InitStructure); + // // Turn on OK LEDs. + // GPIO_ResetBits(etRRGpioSDA.port, etRRGpioSDA.pin); + // GPIO_ResetBits(etRRGpioSCL.port, etRRGpioSCL.pin); + // } return status; } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/interface/deck_spi.h b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/interface/deck_spi.h index c68b7677c..61f3449ae 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/interface/deck_spi.h +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/deck/interface/deck_spi.h @@ -30,6 +30,8 @@ #include <stdbool.h> #include <string.h> +#include "stm32f4xx_spi.h" + // Based on 84MHz peripheral clock #define SPI_BAUDRATE_21MHZ SPI_BaudRatePrescaler_4 // 21MHz #define SPI_BAUDRATE_12MHZ SPI_BaudRatePrescaler_8 // 11.5MHz diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/interface/kalman_core/kalman_core.h b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/interface/kalman_core/kalman_core.h index 3eb84cfc1..6ffba8945 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/interface/kalman_core/kalman_core.h +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/interface/kalman_core/kalman_core.h @@ -87,7 +87,8 @@ typedef struct { // The covariance matrix __attribute__((aligned(4))) float P[KC_STATE_DIM][KC_STATE_DIM]; - arm_matrix_instance_f32 Pm; + //COMMENTED FIRMWARE + //arm_matrix_instance_f32 Pm; // Indicates that the internal state is corrupt and should be reset bool resetEstimation; @@ -120,6 +121,7 @@ void kalmanCoreExternalizeState(const kalmanCoreData_t* this, state_t *state, co void kalmanCoreDecoupleXY(kalmanCoreData_t* this); -void kalmanCoreScalarUpdate(kalmanCoreData_t* this, arm_matrix_instance_f32 *Hm, float error, float stdMeasNoise); +//COMMENTED FIRMWARE +// void kalmanCoreScalarUpdate(kalmanCoreData_t* this, arm_matrix_instance_f32 *Hm, float error, float stdMeasNoise); -void kalmanCoreUpdateWithPKE(kalmanCoreData_t* this, arm_matrix_instance_f32 *Hm, arm_matrix_instance_f32 *Km, arm_matrix_instance_f32 *P_w_m, float error); \ No newline at end of file +// void kalmanCoreUpdateWithPKE(kalmanCoreData_t* this, arm_matrix_instance_f32 *Hm, arm_matrix_instance_f32 *Km, arm_matrix_instance_f32 *P_w_m, float error); \ No newline at end of file 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 973e5e454..7d309ccc6 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 @@ -55,6 +55,7 @@ such as: take-off, landing, polynomial trajectories. #include "param.h" #include "static_mem.h" #include "mem.h" +#include "config.h" // Local types enum TrajectoryLocation_e { diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/kalman_core.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/kalman_core.c index 5e92ba761..1cb0f2b58 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/kalman_core.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/kalman_core.c @@ -197,370 +197,375 @@ void kalmanCoreInit(kalmanCoreData_t* this) { this->P[KC_STATE_D1][KC_STATE_D1] = powf(stdDevInitialAttitude_rollpitch, 2); this->P[KC_STATE_D2][KC_STATE_D2] = powf(stdDevInitialAttitude_yaw, 2); - this->Pm.numRows = KC_STATE_DIM; - this->Pm.numCols = KC_STATE_DIM; - this->Pm.pData = (float*)this->P; + //COMMENTED FIRMWARE + // this->Pm.numRows = KC_STATE_DIM; + // this->Pm.numCols = KC_STATE_DIM; + // this->Pm.pData = (float*)this->P; this->baroReferenceHeight = 0.0; } -void kalmanCoreScalarUpdate(kalmanCoreData_t* this, arm_matrix_instance_f32 *Hm, float error, float stdMeasNoise) -{ - // The Kalman gain as a column vector - NO_DMA_CCM_SAFE_ZERO_INIT static float K[KC_STATE_DIM]; - static arm_matrix_instance_f32 Km = {KC_STATE_DIM, 1, (float *)K}; - - // Temporary matrices for the covariance updates - NO_DMA_CCM_SAFE_ZERO_INIT __attribute__((aligned(4))) static float tmpNN1d[KC_STATE_DIM * KC_STATE_DIM]; - static arm_matrix_instance_f32 tmpNN1m = {KC_STATE_DIM, KC_STATE_DIM, tmpNN1d}; - - NO_DMA_CCM_SAFE_ZERO_INIT __attribute__((aligned(4))) static float tmpNN2d[KC_STATE_DIM * KC_STATE_DIM]; - static arm_matrix_instance_f32 tmpNN2m = {KC_STATE_DIM, KC_STATE_DIM, tmpNN2d}; - - NO_DMA_CCM_SAFE_ZERO_INIT __attribute__((aligned(4))) static float tmpNN3d[KC_STATE_DIM * KC_STATE_DIM]; - static arm_matrix_instance_f32 tmpNN3m = {KC_STATE_DIM, KC_STATE_DIM, tmpNN3d}; - - NO_DMA_CCM_SAFE_ZERO_INIT __attribute__((aligned(4))) static float HTd[KC_STATE_DIM * 1]; - static arm_matrix_instance_f32 HTm = {KC_STATE_DIM, 1, HTd}; - - NO_DMA_CCM_SAFE_ZERO_INIT __attribute__((aligned(4))) static float PHTd[KC_STATE_DIM * 1]; - static arm_matrix_instance_f32 PHTm = {KC_STATE_DIM, 1, PHTd}; - - ASSERT(Hm->numRows == 1); - ASSERT(Hm->numCols == KC_STATE_DIM); - - // ====== INNOVATION COVARIANCE ====== - - mat_trans(Hm, &HTm); - mat_mult(&this->Pm, &HTm, &PHTm); // PH' - float R = stdMeasNoise*stdMeasNoise; - float HPHR = R; // HPH' + R - for (int i=0; i<KC_STATE_DIM; i++) { // Add the element of HPH' to the above - HPHR += Hm->pData[i]*PHTd[i]; // this obviously only works if the update is scalar (as in this function) - } - ASSERT(!isnan(HPHR)); - - // ====== MEASUREMENT UPDATE ====== - // Calculate the Kalman gain and perform the state update - for (int i=0; i<KC_STATE_DIM; i++) { - K[i] = PHTd[i]/HPHR; // kalman gain = (PH' (HPH' + R )^-1) - this->S[i] = this->S[i] + K[i] * error; // state update - } - assertStateNotNaN(this); - - // ====== COVARIANCE UPDATE ====== - mat_mult(&Km, Hm, &tmpNN1m); // KH - for (int i=0; i<KC_STATE_DIM; i++) { tmpNN1d[KC_STATE_DIM*i+i] -= 1; } // KH - I - mat_trans(&tmpNN1m, &tmpNN2m); // (KH - I)' - mat_mult(&tmpNN1m, &this->Pm, &tmpNN3m); // (KH - I)*P - mat_mult(&tmpNN3m, &tmpNN2m, &this->Pm); // (KH - I)*P*(KH - I)' - assertStateNotNaN(this); - // add the measurement variance and ensure boundedness and symmetry - // TODO: Why would it hit these bounds? Needs to be investigated. - for (int i=0; i<KC_STATE_DIM; i++) { - for (int j=i; j<KC_STATE_DIM; j++) { - float v = K[i] * R * K[j]; - float p = 0.5f*this->P[i][j] + 0.5f*this->P[j][i] + v; // add measurement noise - if (isnan(p) || p > MAX_COVARIANCE) { - this->P[i][j] = this->P[j][i] = MAX_COVARIANCE; - } else if ( i==j && p < MIN_COVARIANCE ) { - this->P[i][j] = this->P[j][i] = MIN_COVARIANCE; - } else { - this->P[i][j] = this->P[j][i] = p; - } - } - } - - assertStateNotNaN(this); -} - -void kalmanCoreUpdateWithPKE(kalmanCoreData_t* this, arm_matrix_instance_f32 *Hm, arm_matrix_instance_f32 *Km, arm_matrix_instance_f32 *P_w_m, float error) -{ - // kalman filter update with weighted covariance matrix P_w_m, kalman gain Km, and innovation error - // Temporary matrices for the covariance updates - static float tmpNN1d[KC_STATE_DIM][KC_STATE_DIM]; - static arm_matrix_instance_f32 tmpNN1m = {KC_STATE_DIM, KC_STATE_DIM, (float *)tmpNN1d}; - for (int i=0; i<KC_STATE_DIM; i++){ - this->S[i] = this->S[i] + Km->pData[i] * error; - } - // ====== COVARIANCE UPDATE ====== // - mat_mult(Km, Hm, &tmpNN1m); // KH, the Kalman Gain and H are the updated Kalman Gain and H - mat_scale(&tmpNN1m, -1.0f, &tmpNN1m); // I-KH - for (int i=0; i<KC_STATE_DIM; i++) { tmpNN1d[i][i] = 1.0f + tmpNN1d[i][i]; } - float Ppo[KC_STATE_DIM][KC_STATE_DIM]={0}; - arm_matrix_instance_f32 Ppom = {KC_STATE_DIM, KC_STATE_DIM, (float *)Ppo}; - mat_mult(&tmpNN1m, P_w_m, &Ppom); // Pm = (I-KH)*P_w_m - matrixcopy(KC_STATE_DIM, KC_STATE_DIM, this->P, Ppo); - - assertStateNotNaN(this); - - for (int i=0; i<KC_STATE_DIM; i++) { - for (int j=i; j<KC_STATE_DIM; j++) { - float p = 0.5f*this->P[i][j] + 0.5f*this->P[j][i]; - if (isnan(p) || p > MAX_COVARIANCE) { - this->P[i][j] = this->P[j][i] = MAX_COVARIANCE; - } else if ( i==j && p < MIN_COVARIANCE ) { - this->P[i][j] = this->P[j][i] = MIN_COVARIANCE; - } else { - this->P[i][j] = this->P[j][i] = p; - } - } - } - assertStateNotNaN(this); - -} - - -void kalmanCoreUpdateWithBaro(kalmanCoreData_t* this, float baroAsl, bool quadIsFlying) -{ - float h[KC_STATE_DIM] = {0}; - arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; - - h[KC_STATE_Z] = 1; - - if (!quadIsFlying || this->baroReferenceHeight < 1) { - //TODO: maybe we could track the zero height as a state. Would be especially useful if UWB anchors had barometers. - this->baroReferenceHeight = baroAsl; - } - - float meas = (baroAsl - this->baroReferenceHeight); - kalmanCoreScalarUpdate(this, &H, meas - this->S[KC_STATE_Z], measNoiseBaro); -} - -void kalmanCorePredict(kalmanCoreData_t* this, Axis3f *acc, Axis3f *gyro, float dt, bool quadIsFlying) -{ - /* Here we discretize (euler forward) and linearise the quadrocopter dynamics in order - * to push the covariance forward. - * - * QUADROCOPTER DYNAMICS (see paper): - * - * \dot{x} = R(I + [[d]])p - * \dot{p} = f/m * e3 - [[\omega]]p - g(I - [[d]])R^-1 e3 //drag negligible - * \dot{d} = \omega - * - * where [[.]] is the cross-product matrix of . - * \omega are the gyro measurements - * e3 is the column vector [0 0 1]' - * I is the identity - * R is the current attitude as a rotation matrix - * f/m is the mass-normalized motor force (acceleration in the body's z direction) - * g is gravity - * x, p, d are the quad's states - * note that d (attitude error) is zero at the beginning of each iteration, - * since error information is incorporated into R after each Kalman update. - */ - - // The linearized update matrix - NO_DMA_CCM_SAFE_ZERO_INIT static float A[KC_STATE_DIM][KC_STATE_DIM]; - static __attribute__((aligned(4))) arm_matrix_instance_f32 Am = { KC_STATE_DIM, KC_STATE_DIM, (float *)A}; // linearized dynamics for covariance update; - - // Temporary matrices for the covariance updates - NO_DMA_CCM_SAFE_ZERO_INIT static float tmpNN1d[KC_STATE_DIM * KC_STATE_DIM]; - static __attribute__((aligned(4))) arm_matrix_instance_f32 tmpNN1m = { KC_STATE_DIM, KC_STATE_DIM, tmpNN1d}; - - NO_DMA_CCM_SAFE_ZERO_INIT static float tmpNN2d[KC_STATE_DIM * KC_STATE_DIM]; - static __attribute__((aligned(4))) arm_matrix_instance_f32 tmpNN2m = { KC_STATE_DIM, KC_STATE_DIM, tmpNN2d}; - - float dt2 = dt*dt; - - // ====== DYNAMICS LINEARIZATION ====== - // Initialize as the identity - A[KC_STATE_X][KC_STATE_X] = 1; - A[KC_STATE_Y][KC_STATE_Y] = 1; - A[KC_STATE_Z][KC_STATE_Z] = 1; - - A[KC_STATE_PX][KC_STATE_PX] = 1; - A[KC_STATE_PY][KC_STATE_PY] = 1; - A[KC_STATE_PZ][KC_STATE_PZ] = 1; - - A[KC_STATE_D0][KC_STATE_D0] = 1; - A[KC_STATE_D1][KC_STATE_D1] = 1; - A[KC_STATE_D2][KC_STATE_D2] = 1; - - // position from body-frame velocity - A[KC_STATE_X][KC_STATE_PX] = this->R[0][0]*dt; - A[KC_STATE_Y][KC_STATE_PX] = this->R[1][0]*dt; - A[KC_STATE_Z][KC_STATE_PX] = this->R[2][0]*dt; - - A[KC_STATE_X][KC_STATE_PY] = this->R[0][1]*dt; - A[KC_STATE_Y][KC_STATE_PY] = this->R[1][1]*dt; - A[KC_STATE_Z][KC_STATE_PY] = this->R[2][1]*dt; - - A[KC_STATE_X][KC_STATE_PZ] = this->R[0][2]*dt; - A[KC_STATE_Y][KC_STATE_PZ] = this->R[1][2]*dt; - A[KC_STATE_Z][KC_STATE_PZ] = this->R[2][2]*dt; - - // position from attitude error - A[KC_STATE_X][KC_STATE_D0] = (this->S[KC_STATE_PY]*this->R[0][2] - this->S[KC_STATE_PZ]*this->R[0][1])*dt; - A[KC_STATE_Y][KC_STATE_D0] = (this->S[KC_STATE_PY]*this->R[1][2] - this->S[KC_STATE_PZ]*this->R[1][1])*dt; - A[KC_STATE_Z][KC_STATE_D0] = (this->S[KC_STATE_PY]*this->R[2][2] - this->S[KC_STATE_PZ]*this->R[2][1])*dt; - - A[KC_STATE_X][KC_STATE_D1] = (- this->S[KC_STATE_PX]*this->R[0][2] + this->S[KC_STATE_PZ]*this->R[0][0])*dt; - A[KC_STATE_Y][KC_STATE_D1] = (- this->S[KC_STATE_PX]*this->R[1][2] + this->S[KC_STATE_PZ]*this->R[1][0])*dt; - A[KC_STATE_Z][KC_STATE_D1] = (- this->S[KC_STATE_PX]*this->R[2][2] + this->S[KC_STATE_PZ]*this->R[2][0])*dt; - - A[KC_STATE_X][KC_STATE_D2] = (this->S[KC_STATE_PX]*this->R[0][1] - this->S[KC_STATE_PY]*this->R[0][0])*dt; - A[KC_STATE_Y][KC_STATE_D2] = (this->S[KC_STATE_PX]*this->R[1][1] - this->S[KC_STATE_PY]*this->R[1][0])*dt; - A[KC_STATE_Z][KC_STATE_D2] = (this->S[KC_STATE_PX]*this->R[2][1] - this->S[KC_STATE_PY]*this->R[2][0])*dt; - - // body-frame velocity from body-frame velocity - A[KC_STATE_PX][KC_STATE_PX] = 1; //drag negligible - A[KC_STATE_PY][KC_STATE_PX] =-gyro->z*dt; - A[KC_STATE_PZ][KC_STATE_PX] = gyro->y*dt; - - A[KC_STATE_PX][KC_STATE_PY] = gyro->z*dt; - A[KC_STATE_PY][KC_STATE_PY] = 1; //drag negligible - A[KC_STATE_PZ][KC_STATE_PY] =-gyro->x*dt; - - A[KC_STATE_PX][KC_STATE_PZ] =-gyro->y*dt; - A[KC_STATE_PY][KC_STATE_PZ] = gyro->x*dt; - A[KC_STATE_PZ][KC_STATE_PZ] = 1; //drag negligible - - // body-frame velocity from attitude error - A[KC_STATE_PX][KC_STATE_D0] = 0; - A[KC_STATE_PY][KC_STATE_D0] = -GRAVITY_MAGNITUDE*this->R[2][2]*dt; - A[KC_STATE_PZ][KC_STATE_D0] = GRAVITY_MAGNITUDE*this->R[2][1]*dt; - - A[KC_STATE_PX][KC_STATE_D1] = GRAVITY_MAGNITUDE*this->R[2][2]*dt; - A[KC_STATE_PY][KC_STATE_D1] = 0; - A[KC_STATE_PZ][KC_STATE_D1] = -GRAVITY_MAGNITUDE*this->R[2][0]*dt; - - A[KC_STATE_PX][KC_STATE_D2] = -GRAVITY_MAGNITUDE*this->R[2][1]*dt; - A[KC_STATE_PY][KC_STATE_D2] = GRAVITY_MAGNITUDE*this->R[2][0]*dt; - A[KC_STATE_PZ][KC_STATE_D2] = 0; - - // attitude error from attitude error - /** - * At first glance, it may not be clear where the next values come from, since they do not appear directly in the - * dynamics. In this prediction step, we skip the step of first updating attitude-error, and then incorporating the - * new error into the current attitude (which requires a rotation of the attitude-error covariance). Instead, we - * directly update the body attitude, however still need to rotate the covariance, which is what you see below. - * - * This comes from a second order approximation to: - * Sigma_post = exps(-d) Sigma_pre exps(-d)' - * ~ (I + [[-d]] + [[-d]]^2 / 2) Sigma_pre (I + [[-d]] + [[-d]]^2 / 2)' - * where d is the attitude error expressed as Rodriges parameters, ie. d0 = 1/2*gyro.x*dt under the assumption that - * d = [0,0,0] at the beginning of each prediction step and that gyro.x is constant over the sampling period - * - * As derived in "Covariance Correction Step for Kalman Filtering with an Attitude" - * http://arc.aiaa.org/doi/abs/10.2514/1.G000848 - */ - float d0 = gyro->x*dt/2; - float d1 = gyro->y*dt/2; - float d2 = gyro->z*dt/2; - - A[KC_STATE_D0][KC_STATE_D0] = 1 - d1*d1/2 - d2*d2/2; - A[KC_STATE_D0][KC_STATE_D1] = d2 + d0*d1/2; - A[KC_STATE_D0][KC_STATE_D2] = -d1 + d0*d2/2; - - A[KC_STATE_D1][KC_STATE_D0] = -d2 + d0*d1/2; - A[KC_STATE_D1][KC_STATE_D1] = 1 - d0*d0/2 - d2*d2/2; - A[KC_STATE_D1][KC_STATE_D2] = d0 + d1*d2/2; - - A[KC_STATE_D2][KC_STATE_D0] = d1 + d0*d2/2; - A[KC_STATE_D2][KC_STATE_D1] = -d0 + d1*d2/2; - A[KC_STATE_D2][KC_STATE_D2] = 1 - d0*d0/2 - d1*d1/2; - - - // ====== COVARIANCE UPDATE ====== - mat_mult(&Am, &this->Pm, &tmpNN1m); // A P - mat_trans(&Am, &tmpNN2m); // A' - mat_mult(&tmpNN1m, &tmpNN2m, &this->Pm); // A P A' - // Process noise is added after the return from the prediction step - - // ====== PREDICTION STEP ====== - // The prediction depends on whether we're on the ground, or in flight. - // When flying, the accelerometer directly measures thrust (hence is useless to estimate body angle while flying) - - float dx, dy, dz; - float tmpSPX, tmpSPY, tmpSPZ; - float zacc; - - if (quadIsFlying) // only acceleration in z direction - { - // Use accelerometer and not commanded thrust, as this has proper physical units - zacc = acc->z; - - // position updates in the body frame (will be rotated to inertial frame) - dx = this->S[KC_STATE_PX] * dt; - dy = this->S[KC_STATE_PY] * dt; - dz = this->S[KC_STATE_PZ] * dt + zacc * dt2 / 2.0f; // thrust can only be produced in the body's Z direction - - // position update - this->S[KC_STATE_X] += this->R[0][0] * dx + this->R[0][1] * dy + this->R[0][2] * dz; - this->S[KC_STATE_Y] += this->R[1][0] * dx + this->R[1][1] * dy + this->R[1][2] * dz; - this->S[KC_STATE_Z] += this->R[2][0] * dx + this->R[2][1] * dy + this->R[2][2] * dz - GRAVITY_MAGNITUDE * dt2 / 2.0f; - - // keep previous time step's state for the update - tmpSPX = this->S[KC_STATE_PX]; - tmpSPY = this->S[KC_STATE_PY]; - tmpSPZ = this->S[KC_STATE_PZ]; - - // body-velocity update: accelerometers - gyros cross velocity - gravity in body frame - this->S[KC_STATE_PX] += dt * (gyro->z * tmpSPY - gyro->y * tmpSPZ - GRAVITY_MAGNITUDE * this->R[2][0]); - this->S[KC_STATE_PY] += dt * (-gyro->z * tmpSPX + gyro->x * tmpSPZ - GRAVITY_MAGNITUDE * this->R[2][1]); - this->S[KC_STATE_PZ] += dt * (zacc + gyro->y * tmpSPX - gyro->x * tmpSPY - GRAVITY_MAGNITUDE * this->R[2][2]); - } - else // Acceleration can be in any direction, as measured by the accelerometer. This occurs, eg. in freefall or while being carried. - { - // position updates in the body frame (will be rotated to inertial frame) - dx = this->S[KC_STATE_PX] * dt + acc->x * dt2 / 2.0f; - dy = this->S[KC_STATE_PY] * dt + acc->y * dt2 / 2.0f; - dz = this->S[KC_STATE_PZ] * dt + acc->z * dt2 / 2.0f; // thrust can only be produced in the body's Z direction - - // position update - this->S[KC_STATE_X] += this->R[0][0] * dx + this->R[0][1] * dy + this->R[0][2] * dz; - this->S[KC_STATE_Y] += this->R[1][0] * dx + this->R[1][1] * dy + this->R[1][2] * dz; - this->S[KC_STATE_Z] += this->R[2][0] * dx + this->R[2][1] * dy + this->R[2][2] * dz - GRAVITY_MAGNITUDE * dt2 / 2.0f; - - // keep previous time step's state for the update - tmpSPX = this->S[KC_STATE_PX]; - tmpSPY = this->S[KC_STATE_PY]; - tmpSPZ = this->S[KC_STATE_PZ]; - - // body-velocity update: accelerometers - gyros cross velocity - gravity in body frame - this->S[KC_STATE_PX] += dt * (acc->x + gyro->z * tmpSPY - gyro->y * tmpSPZ - GRAVITY_MAGNITUDE * this->R[2][0]); - this->S[KC_STATE_PY] += dt * (acc->y - gyro->z * tmpSPX + gyro->x * tmpSPZ - GRAVITY_MAGNITUDE * this->R[2][1]); - this->S[KC_STATE_PZ] += dt * (acc->z + gyro->y * tmpSPX - gyro->x * tmpSPY - GRAVITY_MAGNITUDE * this->R[2][2]); - } - - // attitude update (rotate by gyroscope), we do this in quaternions - // this is the gyroscope angular velocity integrated over the sample period - float dtwx = dt*gyro->x; - float dtwy = dt*gyro->y; - float dtwz = dt*gyro->z; - - // compute the quaternion values in [w,x,y,z] order - float angle = arm_sqrt(dtwx*dtwx + dtwy*dtwy + dtwz*dtwz); - float ca = arm_cos_f32(angle/2.0f); - float sa = arm_sin_f32(angle/2.0f); - float dq[4] = {ca , sa*dtwx/angle , sa*dtwy/angle , sa*dtwz/angle}; - - float tmpq0; - float tmpq1; - float tmpq2; - float tmpq3; - - // rotate the quad's attitude by the delta quaternion vector computed above - tmpq0 = dq[0]*this->q[0] - dq[1]*this->q[1] - dq[2]*this->q[2] - dq[3]*this->q[3]; - tmpq1 = dq[1]*this->q[0] + dq[0]*this->q[1] + dq[3]*this->q[2] - dq[2]*this->q[3]; - tmpq2 = dq[2]*this->q[0] - dq[3]*this->q[1] + dq[0]*this->q[2] + dq[1]*this->q[3]; - tmpq3 = dq[3]*this->q[0] + dq[2]*this->q[1] - dq[1]*this->q[2] + dq[0]*this->q[3]; - - if (! quadIsFlying) { - float keep = 1.0f - ROLLPITCH_ZERO_REVERSION; - - tmpq0 = keep * tmpq0 + ROLLPITCH_ZERO_REVERSION * initialQuaternion[0]; - tmpq1 = keep * tmpq1 + ROLLPITCH_ZERO_REVERSION * initialQuaternion[1]; - tmpq2 = keep * tmpq2 + ROLLPITCH_ZERO_REVERSION * initialQuaternion[2]; - tmpq3 = keep * tmpq3 + ROLLPITCH_ZERO_REVERSION * initialQuaternion[3]; - } - - // normalize and store the result - float norm = arm_sqrt(tmpq0*tmpq0 + tmpq1*tmpq1 + tmpq2*tmpq2 + tmpq3*tmpq3); - this->q[0] = tmpq0/norm; this->q[1] = tmpq1/norm; this->q[2] = tmpq2/norm; this->q[3] = tmpq3/norm; - assertStateNotNaN(this); -} +//COMMENTED FIRMWARE +// void kalmanCoreScalarUpdate(kalmanCoreData_t* this, arm_matrix_instance_f32 *Hm, float error, float stdMeasNoise) +// { +// // The Kalman gain as a column vector +// NO_DMA_CCM_SAFE_ZERO_INIT static float K[KC_STATE_DIM]; +// static arm_matrix_instance_f32 Km = {KC_STATE_DIM, 1, (float *)K}; + +// // Temporary matrices for the covariance updates +// NO_DMA_CCM_SAFE_ZERO_INIT __attribute__((aligned(4))) static float tmpNN1d[KC_STATE_DIM * KC_STATE_DIM]; +// static arm_matrix_instance_f32 tmpNN1m = {KC_STATE_DIM, KC_STATE_DIM, tmpNN1d}; + +// NO_DMA_CCM_SAFE_ZERO_INIT __attribute__((aligned(4))) static float tmpNN2d[KC_STATE_DIM * KC_STATE_DIM]; +// static arm_matrix_instance_f32 tmpNN2m = {KC_STATE_DIM, KC_STATE_DIM, tmpNN2d}; + +// NO_DMA_CCM_SAFE_ZERO_INIT __attribute__((aligned(4))) static float tmpNN3d[KC_STATE_DIM * KC_STATE_DIM]; +// static arm_matrix_instance_f32 tmpNN3m = {KC_STATE_DIM, KC_STATE_DIM, tmpNN3d}; + +// NO_DMA_CCM_SAFE_ZERO_INIT __attribute__((aligned(4))) static float HTd[KC_STATE_DIM * 1]; +// static arm_matrix_instance_f32 HTm = {KC_STATE_DIM, 1, HTd}; + +// NO_DMA_CCM_SAFE_ZERO_INIT __attribute__((aligned(4))) static float PHTd[KC_STATE_DIM * 1]; +// static arm_matrix_instance_f32 PHTm = {KC_STATE_DIM, 1, PHTd}; + +// ASSERT(Hm->numRows == 1); +// ASSERT(Hm->numCols == KC_STATE_DIM); + +// // ====== INNOVATION COVARIANCE ====== + +// mat_trans(Hm, &HTm); +// mat_mult(&this->Pm, &HTm, &PHTm); // PH' +// float R = stdMeasNoise*stdMeasNoise; +// float HPHR = R; // HPH' + R +// for (int i=0; i<KC_STATE_DIM; i++) { // Add the element of HPH' to the above +// HPHR += Hm->pData[i]*PHTd[i]; // this obviously only works if the update is scalar (as in this function) +// } +// ASSERT(!isnan(HPHR)); + +// // ====== MEASUREMENT UPDATE ====== +// // Calculate the Kalman gain and perform the state update +// for (int i=0; i<KC_STATE_DIM; i++) { +// K[i] = PHTd[i]/HPHR; // kalman gain = (PH' (HPH' + R )^-1) +// this->S[i] = this->S[i] + K[i] * error; // state update +// } +// assertStateNotNaN(this); + +// // ====== COVARIANCE UPDATE ====== +// mat_mult(&Km, Hm, &tmpNN1m); // KH +// for (int i=0; i<KC_STATE_DIM; i++) { tmpNN1d[KC_STATE_DIM*i+i] -= 1; } // KH - I +// mat_trans(&tmpNN1m, &tmpNN2m); // (KH - I)' +// mat_mult(&tmpNN1m, &this->Pm, &tmpNN3m); // (KH - I)*P +// mat_mult(&tmpNN3m, &tmpNN2m, &this->Pm); // (KH - I)*P*(KH - I)' +// assertStateNotNaN(this); +// // add the measurement variance and ensure boundedness and symmetry +// // TODO: Why would it hit these bounds? Needs to be investigated. +// for (int i=0; i<KC_STATE_DIM; i++) { +// for (int j=i; j<KC_STATE_DIM; j++) { +// float v = K[i] * R * K[j]; +// float p = 0.5f*this->P[i][j] + 0.5f*this->P[j][i] + v; // add measurement noise +// if (isnan(p) || p > MAX_COVARIANCE) { +// this->P[i][j] = this->P[j][i] = MAX_COVARIANCE; +// } else if ( i==j && p < MIN_COVARIANCE ) { +// this->P[i][j] = this->P[j][i] = MIN_COVARIANCE; +// } else { +// this->P[i][j] = this->P[j][i] = p; +// } +// } +// } + +// assertStateNotNaN(this); +// } + +//COMMENTED FIRMWARE +// void kalmanCoreUpdateWithPKE(kalmanCoreData_t* this, arm_matrix_instance_f32 *Hm, arm_matrix_instance_f32 *Km, arm_matrix_instance_f32 *P_w_m, float error) +// { +// // kalman filter update with weighted covariance matrix P_w_m, kalman gain Km, and innovation error +// // Temporary matrices for the covariance updates +// static float tmpNN1d[KC_STATE_DIM][KC_STATE_DIM]; +// static arm_matrix_instance_f32 tmpNN1m = {KC_STATE_DIM, KC_STATE_DIM, (float *)tmpNN1d}; +// for (int i=0; i<KC_STATE_DIM; i++){ +// this->S[i] = this->S[i] + Km->pData[i] * error; +// } +// // ====== COVARIANCE UPDATE ====== // +// mat_mult(Km, Hm, &tmpNN1m); // KH, the Kalman Gain and H are the updated Kalman Gain and H +// mat_scale(&tmpNN1m, -1.0f, &tmpNN1m); // I-KH +// for (int i=0; i<KC_STATE_DIM; i++) { tmpNN1d[i][i] = 1.0f + tmpNN1d[i][i]; } +// float Ppo[KC_STATE_DIM][KC_STATE_DIM]={0}; +// arm_matrix_instance_f32 Ppom = {KC_STATE_DIM, KC_STATE_DIM, (float *)Ppo}; +// mat_mult(&tmpNN1m, P_w_m, &Ppom); // Pm = (I-KH)*P_w_m +// matrixcopy(KC_STATE_DIM, KC_STATE_DIM, this->P, Ppo); + +// assertStateNotNaN(this); + +// for (int i=0; i<KC_STATE_DIM; i++) { +// for (int j=i; j<KC_STATE_DIM; j++) { +// float p = 0.5f*this->P[i][j] + 0.5f*this->P[j][i]; +// if (isnan(p) || p > MAX_COVARIANCE) { +// this->P[i][j] = this->P[j][i] = MAX_COVARIANCE; +// } else if ( i==j && p < MIN_COVARIANCE ) { +// this->P[i][j] = this->P[j][i] = MIN_COVARIANCE; +// } else { +// this->P[i][j] = this->P[j][i] = p; +// } +// } +// } +// assertStateNotNaN(this); + +// } + +//COMMENTED FIRMWARE +// void kalmanCoreUpdateWithBaro(kalmanCoreData_t* this, float baroAsl, bool quadIsFlying) +// { +// float h[KC_STATE_DIM] = {0}; +// arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; + +// h[KC_STATE_Z] = 1; + +// if (!quadIsFlying || this->baroReferenceHeight < 1) { +// //TODO: maybe we could track the zero height as a state. Would be especially useful if UWB anchors had barometers. +// this->baroReferenceHeight = baroAsl; +// } + +// float meas = (baroAsl - this->baroReferenceHeight); +// kalmanCoreScalarUpdate(this, &H, meas - this->S[KC_STATE_Z], measNoiseBaro); +// } + +//COMMENTED FIRMWARE +// void kalmanCorePredict(kalmanCoreData_t* this, Axis3f *acc, Axis3f *gyro, float dt, bool quadIsFlying) +// { +// /* Here we discretize (euler forward) and linearise the quadrocopter dynamics in order +// * to push the covariance forward. +// * +// * QUADROCOPTER DYNAMICS (see paper): +// * +// * \dot{x} = R(I + [[d]])p +// * \dot{p} = f/m * e3 - [[\omega]]p - g(I - [[d]])R^-1 e3 //drag negligible +// * \dot{d} = \omega +// * +// * where [[.]] is the cross-product matrix of . +// * \omega are the gyro measurements +// * e3 is the column vector [0 0 1]' +// * I is the identity +// * R is the current attitude as a rotation matrix +// * f/m is the mass-normalized motor force (acceleration in the body's z direction) +// * g is gravity +// * x, p, d are the quad's states +// * note that d (attitude error) is zero at the beginning of each iteration, +// * since error information is incorporated into R after each Kalman update. +// */ + +// // The linearized update matrix +// //COMMENTED FIRMWARE +// NO_DMA_CCM_SAFE_ZERO_INIT static float A[KC_STATE_DIM][KC_STATE_DIM]; +// static __attribute__((aligned(4))) arm_matrix_instance_f32 Am = { KC_STATE_DIM, KC_STATE_DIM, (float *)A}; // linearized dynamics for covariance update; + +// // Temporary matrices for the covariance updates +// NO_DMA_CCM_SAFE_ZERO_INIT static float tmpNN1d[KC_STATE_DIM * KC_STATE_DIM]; +// static __attribute__((aligned(4))) arm_matrix_instance_f32 tmpNN1m = { KC_STATE_DIM, KC_STATE_DIM, tmpNN1d}; + +// NO_DMA_CCM_SAFE_ZERO_INIT static float tmpNN2d[KC_STATE_DIM * KC_STATE_DIM]; +// static __attribute__((aligned(4))) arm_matrix_instance_f32 tmpNN2m = { KC_STATE_DIM, KC_STATE_DIM, tmpNN2d}; + +// float dt2 = dt*dt; + +// // ====== DYNAMICS LINEARIZATION ====== +// // Initialize as the identity +// A[KC_STATE_X][KC_STATE_X] = 1; +// A[KC_STATE_Y][KC_STATE_Y] = 1; +// A[KC_STATE_Z][KC_STATE_Z] = 1; + +// A[KC_STATE_PX][KC_STATE_PX] = 1; +// A[KC_STATE_PY][KC_STATE_PY] = 1; +// A[KC_STATE_PZ][KC_STATE_PZ] = 1; + +// A[KC_STATE_D0][KC_STATE_D0] = 1; +// A[KC_STATE_D1][KC_STATE_D1] = 1; +// A[KC_STATE_D2][KC_STATE_D2] = 1; + +// // position from body-frame velocity +// A[KC_STATE_X][KC_STATE_PX] = this->R[0][0]*dt; +// A[KC_STATE_Y][KC_STATE_PX] = this->R[1][0]*dt; +// A[KC_STATE_Z][KC_STATE_PX] = this->R[2][0]*dt; + +// A[KC_STATE_X][KC_STATE_PY] = this->R[0][1]*dt; +// A[KC_STATE_Y][KC_STATE_PY] = this->R[1][1]*dt; +// A[KC_STATE_Z][KC_STATE_PY] = this->R[2][1]*dt; + +// A[KC_STATE_X][KC_STATE_PZ] = this->R[0][2]*dt; +// A[KC_STATE_Y][KC_STATE_PZ] = this->R[1][2]*dt; +// A[KC_STATE_Z][KC_STATE_PZ] = this->R[2][2]*dt; + +// // position from attitude error +// A[KC_STATE_X][KC_STATE_D0] = (this->S[KC_STATE_PY]*this->R[0][2] - this->S[KC_STATE_PZ]*this->R[0][1])*dt; +// A[KC_STATE_Y][KC_STATE_D0] = (this->S[KC_STATE_PY]*this->R[1][2] - this->S[KC_STATE_PZ]*this->R[1][1])*dt; +// A[KC_STATE_Z][KC_STATE_D0] = (this->S[KC_STATE_PY]*this->R[2][2] - this->S[KC_STATE_PZ]*this->R[2][1])*dt; + +// A[KC_STATE_X][KC_STATE_D1] = (- this->S[KC_STATE_PX]*this->R[0][2] + this->S[KC_STATE_PZ]*this->R[0][0])*dt; +// A[KC_STATE_Y][KC_STATE_D1] = (- this->S[KC_STATE_PX]*this->R[1][2] + this->S[KC_STATE_PZ]*this->R[1][0])*dt; +// A[KC_STATE_Z][KC_STATE_D1] = (- this->S[KC_STATE_PX]*this->R[2][2] + this->S[KC_STATE_PZ]*this->R[2][0])*dt; + +// A[KC_STATE_X][KC_STATE_D2] = (this->S[KC_STATE_PX]*this->R[0][1] - this->S[KC_STATE_PY]*this->R[0][0])*dt; +// A[KC_STATE_Y][KC_STATE_D2] = (this->S[KC_STATE_PX]*this->R[1][1] - this->S[KC_STATE_PY]*this->R[1][0])*dt; +// A[KC_STATE_Z][KC_STATE_D2] = (this->S[KC_STATE_PX]*this->R[2][1] - this->S[KC_STATE_PY]*this->R[2][0])*dt; + +// // body-frame velocity from body-frame velocity +// A[KC_STATE_PX][KC_STATE_PX] = 1; //drag negligible +// A[KC_STATE_PY][KC_STATE_PX] =-gyro->z*dt; +// A[KC_STATE_PZ][KC_STATE_PX] = gyro->y*dt; + +// A[KC_STATE_PX][KC_STATE_PY] = gyro->z*dt; +// A[KC_STATE_PY][KC_STATE_PY] = 1; //drag negligible +// A[KC_STATE_PZ][KC_STATE_PY] =-gyro->x*dt; + +// A[KC_STATE_PX][KC_STATE_PZ] =-gyro->y*dt; +// A[KC_STATE_PY][KC_STATE_PZ] = gyro->x*dt; +// A[KC_STATE_PZ][KC_STATE_PZ] = 1; //drag negligible + +// // body-frame velocity from attitude error +// A[KC_STATE_PX][KC_STATE_D0] = 0; +// A[KC_STATE_PY][KC_STATE_D0] = -GRAVITY_MAGNITUDE*this->R[2][2]*dt; +// A[KC_STATE_PZ][KC_STATE_D0] = GRAVITY_MAGNITUDE*this->R[2][1]*dt; + +// A[KC_STATE_PX][KC_STATE_D1] = GRAVITY_MAGNITUDE*this->R[2][2]*dt; +// A[KC_STATE_PY][KC_STATE_D1] = 0; +// A[KC_STATE_PZ][KC_STATE_D1] = -GRAVITY_MAGNITUDE*this->R[2][0]*dt; + +// A[KC_STATE_PX][KC_STATE_D2] = -GRAVITY_MAGNITUDE*this->R[2][1]*dt; +// A[KC_STATE_PY][KC_STATE_D2] = GRAVITY_MAGNITUDE*this->R[2][0]*dt; +// A[KC_STATE_PZ][KC_STATE_D2] = 0; + +// // attitude error from attitude error +// /** +// * At first glance, it may not be clear where the next values come from, since they do not appear directly in the +// * dynamics. In this prediction step, we skip the step of first updating attitude-error, and then incorporating the +// * new error into the current attitude (which requires a rotation of the attitude-error covariance). Instead, we +// * directly update the body attitude, however still need to rotate the covariance, which is what you see below. +// * +// * This comes from a second order approximation to: +// * Sigma_post = exps(-d) Sigma_pre exps(-d)' +// * ~ (I + [[-d]] + [[-d]]^2 / 2) Sigma_pre (I + [[-d]] + [[-d]]^2 / 2)' +// * where d is the attitude error expressed as Rodriges parameters, ie. d0 = 1/2*gyro.x*dt under the assumption that +// * d = [0,0,0] at the beginning of each prediction step and that gyro.x is constant over the sampling period +// * +// * As derived in "Covariance Correction Step for Kalman Filtering with an Attitude" +// * http://arc.aiaa.org/doi/abs/10.2514/1.G000848 +// */ +// float d0 = gyro->x*dt/2; +// float d1 = gyro->y*dt/2; +// float d2 = gyro->z*dt/2; + +// A[KC_STATE_D0][KC_STATE_D0] = 1 - d1*d1/2 - d2*d2/2; +// A[KC_STATE_D0][KC_STATE_D1] = d2 + d0*d1/2; +// A[KC_STATE_D0][KC_STATE_D2] = -d1 + d0*d2/2; + +// A[KC_STATE_D1][KC_STATE_D0] = -d2 + d0*d1/2; +// A[KC_STATE_D1][KC_STATE_D1] = 1 - d0*d0/2 - d2*d2/2; +// A[KC_STATE_D1][KC_STATE_D2] = d0 + d1*d2/2; + +// A[KC_STATE_D2][KC_STATE_D0] = d1 + d0*d2/2; +// A[KC_STATE_D2][KC_STATE_D1] = -d0 + d1*d2/2; +// A[KC_STATE_D2][KC_STATE_D2] = 1 - d0*d0/2 - d1*d1/2; + + +// // ====== COVARIANCE UPDATE ====== +// mat_mult(&Am, &this->Pm, &tmpNN1m); // A P +// mat_trans(&Am, &tmpNN2m); // A' +// mat_mult(&tmpNN1m, &tmpNN2m, &this->Pm); // A P A' +// // Process noise is added after the return from the prediction step + +// // ====== PREDICTION STEP ====== +// // The prediction depends on whether we're on the ground, or in flight. +// // When flying, the accelerometer directly measures thrust (hence is useless to estimate body angle while flying) + +// float dx, dy, dz; +// float tmpSPX, tmpSPY, tmpSPZ; +// float zacc; + +// if (quadIsFlying) // only acceleration in z direction +// { +// // Use accelerometer and not commanded thrust, as this has proper physical units +// zacc = acc->z; + +// // position updates in the body frame (will be rotated to inertial frame) +// dx = this->S[KC_STATE_PX] * dt; +// dy = this->S[KC_STATE_PY] * dt; +// dz = this->S[KC_STATE_PZ] * dt + zacc * dt2 / 2.0f; // thrust can only be produced in the body's Z direction + +// // position update +// this->S[KC_STATE_X] += this->R[0][0] * dx + this->R[0][1] * dy + this->R[0][2] * dz; +// this->S[KC_STATE_Y] += this->R[1][0] * dx + this->R[1][1] * dy + this->R[1][2] * dz; +// this->S[KC_STATE_Z] += this->R[2][0] * dx + this->R[2][1] * dy + this->R[2][2] * dz - GRAVITY_MAGNITUDE * dt2 / 2.0f; + +// // keep previous time step's state for the update +// tmpSPX = this->S[KC_STATE_PX]; +// tmpSPY = this->S[KC_STATE_PY]; +// tmpSPZ = this->S[KC_STATE_PZ]; + +// // body-velocity update: accelerometers - gyros cross velocity - gravity in body frame +// this->S[KC_STATE_PX] += dt * (gyro->z * tmpSPY - gyro->y * tmpSPZ - GRAVITY_MAGNITUDE * this->R[2][0]); +// this->S[KC_STATE_PY] += dt * (-gyro->z * tmpSPX + gyro->x * tmpSPZ - GRAVITY_MAGNITUDE * this->R[2][1]); +// this->S[KC_STATE_PZ] += dt * (zacc + gyro->y * tmpSPX - gyro->x * tmpSPY - GRAVITY_MAGNITUDE * this->R[2][2]); +// } +// else // Acceleration can be in any direction, as measured by the accelerometer. This occurs, eg. in freefall or while being carried. +// { +// // position updates in the body frame (will be rotated to inertial frame) +// dx = this->S[KC_STATE_PX] * dt + acc->x * dt2 / 2.0f; +// dy = this->S[KC_STATE_PY] * dt + acc->y * dt2 / 2.0f; +// dz = this->S[KC_STATE_PZ] * dt + acc->z * dt2 / 2.0f; // thrust can only be produced in the body's Z direction + +// // position update +// this->S[KC_STATE_X] += this->R[0][0] * dx + this->R[0][1] * dy + this->R[0][2] * dz; +// this->S[KC_STATE_Y] += this->R[1][0] * dx + this->R[1][1] * dy + this->R[1][2] * dz; +// this->S[KC_STATE_Z] += this->R[2][0] * dx + this->R[2][1] * dy + this->R[2][2] * dz - GRAVITY_MAGNITUDE * dt2 / 2.0f; + +// // keep previous time step's state for the update +// tmpSPX = this->S[KC_STATE_PX]; +// tmpSPY = this->S[KC_STATE_PY]; +// tmpSPZ = this->S[KC_STATE_PZ]; + +// // body-velocity update: accelerometers - gyros cross velocity - gravity in body frame +// this->S[KC_STATE_PX] += dt * (acc->x + gyro->z * tmpSPY - gyro->y * tmpSPZ - GRAVITY_MAGNITUDE * this->R[2][0]); +// this->S[KC_STATE_PY] += dt * (acc->y - gyro->z * tmpSPX + gyro->x * tmpSPZ - GRAVITY_MAGNITUDE * this->R[2][1]); +// this->S[KC_STATE_PZ] += dt * (acc->z + gyro->y * tmpSPX - gyro->x * tmpSPY - GRAVITY_MAGNITUDE * this->R[2][2]); +// } + +// // attitude update (rotate by gyroscope), we do this in quaternions +// // this is the gyroscope angular velocity integrated over the sample period +// float dtwx = dt*gyro->x; +// float dtwy = dt*gyro->y; +// float dtwz = dt*gyro->z; + +// // compute the quaternion values in [w,x,y,z] order +// float angle = arm_sqrt(dtwx*dtwx + dtwy*dtwy + dtwz*dtwz); +// float ca = arm_cos_f32(angle/2.0f); +// float sa = arm_sin_f32(angle/2.0f); +// float dq[4] = {ca , sa*dtwx/angle , sa*dtwy/angle , sa*dtwz/angle}; + +// float tmpq0; +// float tmpq1; +// float tmpq2; +// float tmpq3; + +// // rotate the quad's attitude by the delta quaternion vector computed above +// tmpq0 = dq[0]*this->q[0] - dq[1]*this->q[1] - dq[2]*this->q[2] - dq[3]*this->q[3]; +// tmpq1 = dq[1]*this->q[0] + dq[0]*this->q[1] + dq[3]*this->q[2] - dq[2]*this->q[3]; +// tmpq2 = dq[2]*this->q[0] - dq[3]*this->q[1] + dq[0]*this->q[2] + dq[1]*this->q[3]; +// tmpq3 = dq[3]*this->q[0] + dq[2]*this->q[1] - dq[1]*this->q[2] + dq[0]*this->q[3]; + +// if (! quadIsFlying) { +// float keep = 1.0f - ROLLPITCH_ZERO_REVERSION; + +// tmpq0 = keep * tmpq0 + ROLLPITCH_ZERO_REVERSION * initialQuaternion[0]; +// tmpq1 = keep * tmpq1 + ROLLPITCH_ZERO_REVERSION * initialQuaternion[1]; +// tmpq2 = keep * tmpq2 + ROLLPITCH_ZERO_REVERSION * initialQuaternion[2]; +// tmpq3 = keep * tmpq3 + ROLLPITCH_ZERO_REVERSION * initialQuaternion[3]; +// } + +// // normalize and store the result +// float norm = arm_sqrt(tmpq0*tmpq0 + tmpq1*tmpq1 + tmpq2*tmpq2 + tmpq3*tmpq3); +// this->q[0] = tmpq0/norm; this->q[1] = tmpq1/norm; this->q[2] = tmpq2/norm; this->q[3] = tmpq3/norm; +// assertStateNotNaN(this); +// } void kalmanCoreAddProcessNoise(kalmanCoreData_t* this, float dt) @@ -597,120 +602,120 @@ void kalmanCoreAddProcessNoise(kalmanCoreData_t* this, float dt) } - -void kalmanCoreFinalize(kalmanCoreData_t* this, uint32_t tick) -{ - // Matrix to rotate the attitude covariances once updated - NO_DMA_CCM_SAFE_ZERO_INIT static float A[KC_STATE_DIM][KC_STATE_DIM]; - static arm_matrix_instance_f32 Am = {KC_STATE_DIM, KC_STATE_DIM, (float *)A}; - - // Temporary matrices for the covariance updates - NO_DMA_CCM_SAFE_ZERO_INIT static float tmpNN1d[KC_STATE_DIM * KC_STATE_DIM]; - static arm_matrix_instance_f32 tmpNN1m = {KC_STATE_DIM, KC_STATE_DIM, tmpNN1d}; - - NO_DMA_CCM_SAFE_ZERO_INIT static float tmpNN2d[KC_STATE_DIM * KC_STATE_DIM]; - static arm_matrix_instance_f32 tmpNN2m = {KC_STATE_DIM, KC_STATE_DIM, tmpNN2d}; - - // Incorporate the attitude error (Kalman filter state) with the attitude - float v0 = this->S[KC_STATE_D0]; - float v1 = this->S[KC_STATE_D1]; - float v2 = this->S[KC_STATE_D2]; - - // Move attitude error into attitude if any of the angle errors are large enough - if ((fabsf(v0) > 0.1e-3f || fabsf(v1) > 0.1e-3f || fabsf(v2) > 0.1e-3f) && (fabsf(v0) < 10 && fabsf(v1) < 10 && fabsf(v2) < 10)) - { - float angle = arm_sqrt(v0*v0 + v1*v1 + v2*v2); - float ca = arm_cos_f32(angle / 2.0f); - float sa = arm_sin_f32(angle / 2.0f); - float dq[4] = {ca, sa * v0 / angle, sa * v1 / angle, sa * v2 / angle}; - - // rotate the quad's attitude by the delta quaternion vector computed above - float tmpq0 = dq[0] * this->q[0] - dq[1] * this->q[1] - dq[2] * this->q[2] - dq[3] * this->q[3]; - float tmpq1 = dq[1] * this->q[0] + dq[0] * this->q[1] + dq[3] * this->q[2] - dq[2] * this->q[3]; - float tmpq2 = dq[2] * this->q[0] - dq[3] * this->q[1] + dq[0] * this->q[2] + dq[1] * this->q[3]; - float tmpq3 = dq[3] * this->q[0] + dq[2] * this->q[1] - dq[1] * this->q[2] + dq[0] * this->q[3]; - - // normalize and store the result - float norm = arm_sqrt(tmpq0 * tmpq0 + tmpq1 * tmpq1 + tmpq2 * tmpq2 + tmpq3 * tmpq3); - this->q[0] = tmpq0 / norm; - this->q[1] = tmpq1 / norm; - this->q[2] = tmpq2 / norm; - this->q[3] = tmpq3 / norm; - - /** Rotate the covariance, since we've rotated the body - * - * This comes from a second order approximation to: - * Sigma_post = exps(-d) Sigma_pre exps(-d)' - * ~ (I + [[-d]] + [[-d]]^2 / 2) Sigma_pre (I + [[-d]] + [[-d]]^2 / 2)' - * where d is the attitude error expressed as Rodriges parameters, ie. d = tan(|v|/2)*v/|v| - * - * As derived in "Covariance Correction Step for Kalman Filtering with an Attitude" - * http://arc.aiaa.org/doi/abs/10.2514/1.G000848 - */ - - float d0 = v0/2; // the attitude error vector (v0,v1,v2) is small, - float d1 = v1/2; // so we use a first order approximation to d0 = tan(|v0|/2)*v0/|v0| - float d2 = v2/2; - - A[KC_STATE_X][KC_STATE_X] = 1; - A[KC_STATE_Y][KC_STATE_Y] = 1; - A[KC_STATE_Z][KC_STATE_Z] = 1; - - A[KC_STATE_PX][KC_STATE_PX] = 1; - A[KC_STATE_PY][KC_STATE_PY] = 1; - A[KC_STATE_PZ][KC_STATE_PZ] = 1; - - A[KC_STATE_D0][KC_STATE_D0] = 1 - d1*d1/2 - d2*d2/2; - A[KC_STATE_D0][KC_STATE_D1] = d2 + d0*d1/2; - A[KC_STATE_D0][KC_STATE_D2] = -d1 + d0*d2/2; - - A[KC_STATE_D1][KC_STATE_D0] = -d2 + d0*d1/2; - A[KC_STATE_D1][KC_STATE_D1] = 1 - d0*d0/2 - d2*d2/2; - A[KC_STATE_D1][KC_STATE_D2] = d0 + d1*d2/2; - - A[KC_STATE_D2][KC_STATE_D0] = d1 + d0*d2/2; - A[KC_STATE_D2][KC_STATE_D1] = -d0 + d1*d2/2; - A[KC_STATE_D2][KC_STATE_D2] = 1 - d0*d0/2 - d1*d1/2; - - mat_trans(&Am, &tmpNN1m); // A' - mat_mult(&Am, &this->Pm, &tmpNN2m); // AP - mat_mult(&tmpNN2m, &tmpNN1m, &this->Pm); //APA' - } - - // convert the new attitude to a rotation matrix, such that we can rotate body-frame velocity and acc - this->R[0][0] = this->q[0] * this->q[0] + this->q[1] * this->q[1] - this->q[2] * this->q[2] - this->q[3] * this->q[3]; - this->R[0][1] = 2 * this->q[1] * this->q[2] - 2 * this->q[0] * this->q[3]; - this->R[0][2] = 2 * this->q[1] * this->q[3] + 2 * this->q[0] * this->q[2]; - - this->R[1][0] = 2 * this->q[1] * this->q[2] + 2 * this->q[0] * this->q[3]; - this->R[1][1] = this->q[0] * this->q[0] - this->q[1] * this->q[1] + this->q[2] * this->q[2] - this->q[3] * this->q[3]; - this->R[1][2] = 2 * this->q[2] * this->q[3] - 2 * this->q[0] * this->q[1]; - - this->R[2][0] = 2 * this->q[1] * this->q[3] - 2 * this->q[0] * this->q[2]; - this->R[2][1] = 2 * this->q[2] * this->q[3] + 2 * this->q[0] * this->q[1]; - this->R[2][2] = this->q[0] * this->q[0] - this->q[1] * this->q[1] - this->q[2] * this->q[2] + this->q[3] * this->q[3]; - - // reset the attitude error - this->S[KC_STATE_D0] = 0; - this->S[KC_STATE_D1] = 0; - this->S[KC_STATE_D2] = 0; - - // enforce symmetry of the covariance matrix, and ensure the values stay bounded - for (int i=0; i<KC_STATE_DIM; i++) { - for (int j=i; j<KC_STATE_DIM; j++) { - float p = 0.5f*this->P[i][j] + 0.5f*this->P[j][i]; - if (isnan(p) || p > MAX_COVARIANCE) { - this->P[i][j] = this->P[j][i] = MAX_COVARIANCE; - } else if ( i==j && p < MIN_COVARIANCE ) { - this->P[i][j] = this->P[j][i] = MIN_COVARIANCE; - } else { - this->P[i][j] = this->P[j][i] = p; - } - } - } - - assertStateNotNaN(this); -} +//COMMENTED FIRMWARE +// void kalmanCoreFinalize(kalmanCoreData_t* this, uint32_t tick) +// { +// // Matrix to rotate the attitude covariances once updated +// NO_DMA_CCM_SAFE_ZERO_INIT static float A[KC_STATE_DIM][KC_STATE_DIM]; +// static arm_matrix_instance_f32 Am = {KC_STATE_DIM, KC_STATE_DIM, (float *)A}; + +// // Temporary matrices for the covariance updates +// NO_DMA_CCM_SAFE_ZERO_INIT static float tmpNN1d[KC_STATE_DIM * KC_STATE_DIM]; +// static arm_matrix_instance_f32 tmpNN1m = {KC_STATE_DIM, KC_STATE_DIM, tmpNN1d}; + +// NO_DMA_CCM_SAFE_ZERO_INIT static float tmpNN2d[KC_STATE_DIM * KC_STATE_DIM]; +// static arm_matrix_instance_f32 tmpNN2m = {KC_STATE_DIM, KC_STATE_DIM, tmpNN2d}; + +// // Incorporate the attitude error (Kalman filter state) with the attitude +// float v0 = this->S[KC_STATE_D0]; +// float v1 = this->S[KC_STATE_D1]; +// float v2 = this->S[KC_STATE_D2]; + +// // Move attitude error into attitude if any of the angle errors are large enough +// if ((fabsf(v0) > 0.1e-3f || fabsf(v1) > 0.1e-3f || fabsf(v2) > 0.1e-3f) && (fabsf(v0) < 10 && fabsf(v1) < 10 && fabsf(v2) < 10)) +// { +// float angle = arm_sqrt(v0*v0 + v1*v1 + v2*v2); +// float ca = arm_cos_f32(angle / 2.0f); +// float sa = arm_sin_f32(angle / 2.0f); +// float dq[4] = {ca, sa * v0 / angle, sa * v1 / angle, sa * v2 / angle}; + +// // rotate the quad's attitude by the delta quaternion vector computed above +// float tmpq0 = dq[0] * this->q[0] - dq[1] * this->q[1] - dq[2] * this->q[2] - dq[3] * this->q[3]; +// float tmpq1 = dq[1] * this->q[0] + dq[0] * this->q[1] + dq[3] * this->q[2] - dq[2] * this->q[3]; +// float tmpq2 = dq[2] * this->q[0] - dq[3] * this->q[1] + dq[0] * this->q[2] + dq[1] * this->q[3]; +// float tmpq3 = dq[3] * this->q[0] + dq[2] * this->q[1] - dq[1] * this->q[2] + dq[0] * this->q[3]; + +// // normalize and store the result +// float norm = arm_sqrt(tmpq0 * tmpq0 + tmpq1 * tmpq1 + tmpq2 * tmpq2 + tmpq3 * tmpq3); +// this->q[0] = tmpq0 / norm; +// this->q[1] = tmpq1 / norm; +// this->q[2] = tmpq2 / norm; +// this->q[3] = tmpq3 / norm; + +// /** Rotate the covariance, since we've rotated the body +// * +// * This comes from a second order approximation to: +// * Sigma_post = exps(-d) Sigma_pre exps(-d)' +// * ~ (I + [[-d]] + [[-d]]^2 / 2) Sigma_pre (I + [[-d]] + [[-d]]^2 / 2)' +// * where d is the attitude error expressed as Rodriges parameters, ie. d = tan(|v|/2)*v/|v| +// * +// * As derived in "Covariance Correction Step for Kalman Filtering with an Attitude" +// * http://arc.aiaa.org/doi/abs/10.2514/1.G000848 +// */ + +// float d0 = v0/2; // the attitude error vector (v0,v1,v2) is small, +// float d1 = v1/2; // so we use a first order approximation to d0 = tan(|v0|/2)*v0/|v0| +// float d2 = v2/2; + +// A[KC_STATE_X][KC_STATE_X] = 1; +// A[KC_STATE_Y][KC_STATE_Y] = 1; +// A[KC_STATE_Z][KC_STATE_Z] = 1; + +// A[KC_STATE_PX][KC_STATE_PX] = 1; +// A[KC_STATE_PY][KC_STATE_PY] = 1; +// A[KC_STATE_PZ][KC_STATE_PZ] = 1; + +// A[KC_STATE_D0][KC_STATE_D0] = 1 - d1*d1/2 - d2*d2/2; +// A[KC_STATE_D0][KC_STATE_D1] = d2 + d0*d1/2; +// A[KC_STATE_D0][KC_STATE_D2] = -d1 + d0*d2/2; + +// A[KC_STATE_D1][KC_STATE_D0] = -d2 + d0*d1/2; +// A[KC_STATE_D1][KC_STATE_D1] = 1 - d0*d0/2 - d2*d2/2; +// A[KC_STATE_D1][KC_STATE_D2] = d0 + d1*d2/2; + +// A[KC_STATE_D2][KC_STATE_D0] = d1 + d0*d2/2; +// A[KC_STATE_D2][KC_STATE_D1] = -d0 + d1*d2/2; +// A[KC_STATE_D2][KC_STATE_D2] = 1 - d0*d0/2 - d1*d1/2; + +// mat_trans(&Am, &tmpNN1m); // A' +// mat_mult(&Am, &this->Pm, &tmpNN2m); // AP +// mat_mult(&tmpNN2m, &tmpNN1m, &this->Pm); //APA' +// } + +// // convert the new attitude to a rotation matrix, such that we can rotate body-frame velocity and acc +// this->R[0][0] = this->q[0] * this->q[0] + this->q[1] * this->q[1] - this->q[2] * this->q[2] - this->q[3] * this->q[3]; +// this->R[0][1] = 2 * this->q[1] * this->q[2] - 2 * this->q[0] * this->q[3]; +// this->R[0][2] = 2 * this->q[1] * this->q[3] + 2 * this->q[0] * this->q[2]; + +// this->R[1][0] = 2 * this->q[1] * this->q[2] + 2 * this->q[0] * this->q[3]; +// this->R[1][1] = this->q[0] * this->q[0] - this->q[1] * this->q[1] + this->q[2] * this->q[2] - this->q[3] * this->q[3]; +// this->R[1][2] = 2 * this->q[2] * this->q[3] - 2 * this->q[0] * this->q[1]; + +// this->R[2][0] = 2 * this->q[1] * this->q[3] - 2 * this->q[0] * this->q[2]; +// this->R[2][1] = 2 * this->q[2] * this->q[3] + 2 * this->q[0] * this->q[1]; +// this->R[2][2] = this->q[0] * this->q[0] - this->q[1] * this->q[1] - this->q[2] * this->q[2] + this->q[3] * this->q[3]; + +// // reset the attitude error +// this->S[KC_STATE_D0] = 0; +// this->S[KC_STATE_D1] = 0; +// this->S[KC_STATE_D2] = 0; + +// // enforce symmetry of the covariance matrix, and ensure the values stay bounded +// for (int i=0; i<KC_STATE_DIM; i++) { +// for (int j=i; j<KC_STATE_DIM; j++) { +// float p = 0.5f*this->P[i][j] + 0.5f*this->P[j][i]; +// if (isnan(p) || p > MAX_COVARIANCE) { +// this->P[i][j] = this->P[j][i] = MAX_COVARIANCE; +// } else if ( i==j && p < MIN_COVARIANCE ) { +// this->P[i][j] = this->P[j][i] = MIN_COVARIANCE; +// } else { +// this->P[i][j] = this->P[j][i] = p; +// } +// } +// } + +// assertStateNotNaN(this); +// } void kalmanCoreExternalizeState(const kalmanCoreData_t* this, state_t *state, const Axis3f *acc, uint32_t tick) { diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_absolute_height.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_absolute_height.c index 8d41ba9eb..fa009ef40 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_absolute_height.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_absolute_height.c @@ -27,8 +27,9 @@ // Measurement model where the measurement is the absolute height void kalmanCoreUpdateWithAbsoluteHeight(kalmanCoreData_t* this, heightMeasurement_t* height) { - float h[KC_STATE_DIM] = {0}; - arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; - h[KC_STATE_Z] = 1; - kalmanCoreScalarUpdate(this, &H, height->height - this->S[KC_STATE_Z], height->stdDev); + //COMMENTED FIRMWARE + // float h[KC_STATE_DIM] = {0}; + // arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; + // h[KC_STATE_Z] = 1; + // kalmanCoreScalarUpdate(this, &H, height->height - this->S[KC_STATE_Z], height->stdDev); } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_distance.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_distance.c index 68fd7a6d5..2c9306966 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_distance.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_distance.c @@ -28,27 +28,28 @@ // Measurement model where the measurement is the distance to a known point in space void kalmanCoreUpdateWithDistance(kalmanCoreData_t* this, distanceMeasurement_t* d) { // a measurement of distance to point (x, y, z) - float h[KC_STATE_DIM] = {0}; - arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; + //COMMENTED FIRMWARE + // float h[KC_STATE_DIM] = {0}; + // arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; - float dx = this->S[KC_STATE_X] - d->x; - float dy = this->S[KC_STATE_Y] - d->y; - float dz = this->S[KC_STATE_Z] - d->z; + // float dx = this->S[KC_STATE_X] - d->x; + // float dy = this->S[KC_STATE_Y] - d->y; + // float dz = this->S[KC_STATE_Z] - d->z; - float measuredDistance = d->distance; + // float measuredDistance = d->distance; - float predictedDistance = arm_sqrt(powf(dx, 2) + powf(dy, 2) + powf(dz, 2)); - if (predictedDistance != 0.0f) { - // The measurement is: z = sqrt(dx^2 + dy^2 + dz^2). The derivative dz/dX gives h. - h[KC_STATE_X] = dx/predictedDistance; - h[KC_STATE_Y] = dy/predictedDistance; - h[KC_STATE_Z] = dz/predictedDistance; - } else { - // Avoid divide by zero - h[KC_STATE_X] = 1.0f; - h[KC_STATE_Y] = 0.0f; - h[KC_STATE_Z] = 0.0f; - } + // float predictedDistance = arm_sqrt(powf(dx, 2) + powf(dy, 2) + powf(dz, 2)); + // if (predictedDistance != 0.0f) { + // // The measurement is: z = sqrt(dx^2 + dy^2 + dz^2). The derivative dz/dX gives h. + // h[KC_STATE_X] = dx/predictedDistance; + // h[KC_STATE_Y] = dy/predictedDistance; + // h[KC_STATE_Z] = dz/predictedDistance; + // } else { + // // Avoid divide by zero + // h[KC_STATE_X] = 1.0f; + // h[KC_STATE_Y] = 0.0f; + // h[KC_STATE_Z] = 0.0f; + // } - kalmanCoreScalarUpdate(this, &H, measuredDistance-predictedDistance, d->stdDev); + // kalmanCoreScalarUpdate(this, &H, measuredDistance-predictedDistance, d->stdDev); } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_distance_robust.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_distance_robust.c index 9b12da3df..e0662bd38 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_distance_robust.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_distance_robust.c @@ -64,170 +64,171 @@ static void GM_state(float e, float * GM_e){ // robsut update function void kalmanCoreRobustUpdateWithDistance(kalmanCoreData_t* this, distanceMeasurement_t *d) { - float dx = this->S[KC_STATE_X] - d->x; - float dy = this->S[KC_STATE_Y] - d->y; - float dz = this->S[KC_STATE_Z] - d->z; - float measuredDistance = d->distance; - - float predictedDistance = arm_sqrt(powf(dx, 2) + powf(dy, 2) + powf(dz, 2)); - // innovation term based on x_check - float error_check = measuredDistance - predictedDistance; // innovation term based on prior state - // ---------------------- matrix defination ----------------------------- // - static float P_chol[KC_STATE_DIM][KC_STATE_DIM]; - static arm_matrix_instance_f32 Pc_m = {KC_STATE_DIM, KC_STATE_DIM, (float *)P_chol}; - static float Pc_tran[KC_STATE_DIM][KC_STATE_DIM]; - static arm_matrix_instance_f32 Pc_tran_m = {KC_STATE_DIM, KC_STATE_DIM, (float *)Pc_tran}; - - float h[KC_STATE_DIM] = {0}; - arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; - // The Kalman gain as a column vector - static float Kw[KC_STATE_DIM]; - static arm_matrix_instance_f32 Kwm = {KC_STATE_DIM, 1, (float *)Kw}; - - static float e_x[KC_STATE_DIM]; - static arm_matrix_instance_f32 e_x_m = {KC_STATE_DIM, 1, e_x}; - - static float Pc_inv[KC_STATE_DIM][KC_STATE_DIM]; - static arm_matrix_instance_f32 Pc_inv_m = {KC_STATE_DIM, KC_STATE_DIM, (float *)Pc_inv}; - - // rescale matrix - static float wx_inv[KC_STATE_DIM][KC_STATE_DIM]; - static arm_matrix_instance_f32 wx_invm = {KC_STATE_DIM, KC_STATE_DIM, (float *)wx_inv}; - // tmp matrix for P_chol inverse - static float tmp1[KC_STATE_DIM][KC_STATE_DIM]; - static arm_matrix_instance_f32 tmp1m = {KC_STATE_DIM, KC_STATE_DIM, (float *)tmp1}; - - static float Pc_w_inv[KC_STATE_DIM][KC_STATE_DIM]; - static arm_matrix_instance_f32 Pc_w_invm = {KC_STATE_DIM, KC_STATE_DIM, (float *)Pc_w_inv}; - - static float P_w[KC_STATE_DIM][KC_STATE_DIM]; - static arm_matrix_instance_f32 P_w_m = {KC_STATE_DIM, KC_STATE_DIM, (float *)P_w}; - - static float HTd[KC_STATE_DIM]; - static arm_matrix_instance_f32 HTm = {KC_STATE_DIM, 1, HTd}; - - static float PHTd[KC_STATE_DIM]; - static arm_matrix_instance_f32 PHTm = {KC_STATE_DIM, 1, PHTd}; - // ------------------- Initialization -----------------------// - // x prior (error state), set to be zeros. Not used for error state Kalman filter. Provide here for completeness - // float xpr[STATE_DIM] = {0.0}; - - // x_err comes from the KF update is the state of error state Kalman filter, set to be zero initially - static float x_err[KC_STATE_DIM] = {0.0}; - static arm_matrix_instance_f32 x_errm = {KC_STATE_DIM, 1, x_err}; - static float X_state[KC_STATE_DIM] = {0.0}; - float P_iter[KC_STATE_DIM][KC_STATE_DIM]; - matrixcopy(KC_STATE_DIM, KC_STATE_DIM, P_iter,this->P); // init P_iter as P_prior - - float R_iter = d->stdDev * d->stdDev; // measurement covariance - vectorcopy(KC_STATE_DIM, X_state, this->S); // copy Xpr to X_State and then update in each iterations - - // ---------------------- Start iteration ----------------------- // - for (int iter = 0; iter < MAX_ITER; iter++){ - // cholesky decomposition for the prior covariance matrix - Cholesky_Decomposition(KC_STATE_DIM, P_iter, P_chol); // P_chol is a lower triangular matrix - mat_trans(&Pc_m, &Pc_tran_m); - - // decomposition for measurement covariance (scalar case) - float R_chol = sqrtf(R_iter); - // construct H matrix - // X_state updates in each iteration - float x_iter = X_state[KC_STATE_X], y_iter = X_state[KC_STATE_Y], z_iter = X_state[KC_STATE_Z]; - dx = x_iter - d->x; dy = y_iter - d->y; dz = z_iter - d->z; - - float predicted_iter = arm_sqrt(powf(dx, 2) + powf(dy, 2) + powf(dz, 2)); - // innovation term based on x_check - float error_iter = measuredDistance - predicted_iter; - - float e_y = error_iter; - - if (predicted_iter != 0.0f) { - // The measurement is: z = sqrt(dx^2 + dy^2 + dz^2). The derivative dz/dX gives h. - h[KC_STATE_X] = dx/predicted_iter; - h[KC_STATE_Y] = dy/predicted_iter; - h[KC_STATE_Z] = dz/predicted_iter; - - } else { - // Avoid divide by zero - h[KC_STATE_X] = 1.0f; - h[KC_STATE_Y] = 0.0f; - h[KC_STATE_Z] = 0.0f; - } - // check the measurement noise - if (fabsf(R_chol - 0.0f) < 0.0001f){ - e_y = error_iter / 0.0001f; - } - else{ - e_y = error_iter / R_chol; - } - // Make sure P_chol, lower trangular matrix, is numerically stable - for (int col=0; col<KC_STATE_DIM; col++) { - for (int row=col; row<KC_STATE_DIM; row++) { - if (isnan(P_chol[row][col]) || P_chol[row][col] > UPPER_BOUND) { - P_chol[row][col] = UPPER_BOUND; - } else if(row!=col && P_chol[row][col] < LOWER_BOUND){ - P_chol[row][col] = LOWER_BOUND; - } else if(row==col && P_chol[row][col]<0.0f){ - P_chol[row][col] = 0.0f; - } - } - } - // Matrix inversion is numerically sensitive. - // Add small values on the diagonal of P_chol to avoid numerical problems. - float dummy_value = 1e-9f; - for (int k=0; k<KC_STATE_DIM; k++){ - P_chol[k][k] = P_chol[k][k] + dummy_value; - } - // keep P_chol - matrixcopy(KC_STATE_DIM, KC_STATE_DIM, tmp1, P_chol); - mat_inv(&tmp1m, &Pc_inv_m); // Pc_inv_m = inv(Pc_m) = inv(P_chol) - mat_mult(&Pc_inv_m, &x_errm, &e_x_m); // e_x_m = Pc_inv_m.dot(x_errm) - - // compute w_x, w_y --> weighting matrix - // Since w_x is diagnal matrix, directly compute the inverse - for (int state_k = 0; state_k < KC_STATE_DIM; state_k++){ - GM_state(e_x[state_k], &wx_inv[state_k][state_k]); - wx_inv[state_k][state_k] = (float)1.0 / wx_inv[state_k][state_k]; - } - - // rescale covariance matrix P - mat_mult(&Pc_m, &wx_invm, &Pc_w_invm); // Pc_w_invm = P_chol.dot(linalg.inv(w_x)) - mat_mult(&Pc_w_invm, &Pc_tran_m, &P_w_m); // P_w_m = Pc_w_invm.dot(Pc_tran_m) = P_chol.dot(linalg.inv(w_x)).dot(P_chol.T) - - // rescale R matrix - float w_y=0.0; float R_w = 0.0f; - GM_UWB(e_y, &w_y); // compute the weighted measurement error: w_y - if (fabsf(w_y - 0.0f) < 0.0001f){ - R_w = (R_chol * R_chol) / 0.0001f; - } - else{ - R_w = (R_chol * R_chol) / w_y; - } - // ====== INNOVATION COVARIANCE ====== // - - mat_trans(&H, &HTm); - mat_mult(&P_w_m, &HTm, &PHTm); // PHTm = P_w.dot(H.T). The P is the updated P_w - - float HPHR = R_w; // HPH' + R. The R is the updated R_w - for (int i=0; i<KC_STATE_DIM; i++) { // Add the element of HPH' to the above - HPHR += h[i]*PHTd[i]; // this only works if the update is scalar (as in this function) - } - // ====== MEASUREMENT UPDATE ====== - // Calculate the Kalman gain and perform the state update - for (int i=0; i<KC_STATE_DIM; i++) { - Kw[i] = PHTd[i]/HPHR; // rescaled kalman gain = (PH' (HPH' + R )^-1) with the updated P_w and R_w - //[Note]: The error_check here is the innovation term based on x_check, which doesn't change during iterations. - x_err[i] = Kw[i] * error_check; // error state for next iteration - X_state[i] = this->S[i] + x_err[i]; // convert to nominal state - } - // update P_iter matrix and R matrix for next iteration - matrixcopy(KC_STATE_DIM, KC_STATE_DIM, P_iter, P_w); - R_iter = R_w; - } - - - // After n iterations, we obtain the rescaled (1) P = P_iter, (2) R = R_iter, (3) Kw. - // Call the kalman update function with weighted P, weighted K, h, and error_check - kalmanCoreUpdateWithPKE(this, &H, &Kwm, &P_w_m, error_check); + //COMMENTED FIRMWARE + // float dx = this->S[KC_STATE_X] - d->x; + // float dy = this->S[KC_STATE_Y] - d->y; + // float dz = this->S[KC_STATE_Z] - d->z; + // float measuredDistance = d->distance; + + // float predictedDistance = arm_sqrt(powf(dx, 2) + powf(dy, 2) + powf(dz, 2)); + // // innovation term based on x_check + // float error_check = measuredDistance - predictedDistance; // innovation term based on prior state + // // ---------------------- matrix defination ----------------------------- // + // static float P_chol[KC_STATE_DIM][KC_STATE_DIM]; + // static arm_matrix_instance_f32 Pc_m = {KC_STATE_DIM, KC_STATE_DIM, (float *)P_chol}; + // static float Pc_tran[KC_STATE_DIM][KC_STATE_DIM]; + // static arm_matrix_instance_f32 Pc_tran_m = {KC_STATE_DIM, KC_STATE_DIM, (float *)Pc_tran}; + + // float h[KC_STATE_DIM] = {0}; + // arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; + // // The Kalman gain as a column vector + // static float Kw[KC_STATE_DIM]; + // static arm_matrix_instance_f32 Kwm = {KC_STATE_DIM, 1, (float *)Kw}; + + // static float e_x[KC_STATE_DIM]; + // static arm_matrix_instance_f32 e_x_m = {KC_STATE_DIM, 1, e_x}; + + // static float Pc_inv[KC_STATE_DIM][KC_STATE_DIM]; + // static arm_matrix_instance_f32 Pc_inv_m = {KC_STATE_DIM, KC_STATE_DIM, (float *)Pc_inv}; + + // // rescale matrix + // static float wx_inv[KC_STATE_DIM][KC_STATE_DIM]; + // static arm_matrix_instance_f32 wx_invm = {KC_STATE_DIM, KC_STATE_DIM, (float *)wx_inv}; + // // tmp matrix for P_chol inverse + // static float tmp1[KC_STATE_DIM][KC_STATE_DIM]; + // static arm_matrix_instance_f32 tmp1m = {KC_STATE_DIM, KC_STATE_DIM, (float *)tmp1}; + + // static float Pc_w_inv[KC_STATE_DIM][KC_STATE_DIM]; + // static arm_matrix_instance_f32 Pc_w_invm = {KC_STATE_DIM, KC_STATE_DIM, (float *)Pc_w_inv}; + + // static float P_w[KC_STATE_DIM][KC_STATE_DIM]; + // static arm_matrix_instance_f32 P_w_m = {KC_STATE_DIM, KC_STATE_DIM, (float *)P_w}; + + // static float HTd[KC_STATE_DIM]; + // static arm_matrix_instance_f32 HTm = {KC_STATE_DIM, 1, HTd}; + + // static float PHTd[KC_STATE_DIM]; + // static arm_matrix_instance_f32 PHTm = {KC_STATE_DIM, 1, PHTd}; + // // ------------------- Initialization -----------------------// + // // x prior (error state), set to be zeros. Not used for error state Kalman filter. Provide here for completeness + // // float xpr[STATE_DIM] = {0.0}; + + // // x_err comes from the KF update is the state of error state Kalman filter, set to be zero initially + // static float x_err[KC_STATE_DIM] = {0.0}; + // static arm_matrix_instance_f32 x_errm = {KC_STATE_DIM, 1, x_err}; + // static float X_state[KC_STATE_DIM] = {0.0}; + // float P_iter[KC_STATE_DIM][KC_STATE_DIM]; + // matrixcopy(KC_STATE_DIM, KC_STATE_DIM, P_iter,this->P); // init P_iter as P_prior + + // float R_iter = d->stdDev * d->stdDev; // measurement covariance + // vectorcopy(KC_STATE_DIM, X_state, this->S); // copy Xpr to X_State and then update in each iterations + + // // ---------------------- Start iteration ----------------------- // + // for (int iter = 0; iter < MAX_ITER; iter++){ + // // cholesky decomposition for the prior covariance matrix + // Cholesky_Decomposition(KC_STATE_DIM, P_iter, P_chol); // P_chol is a lower triangular matrix + // mat_trans(&Pc_m, &Pc_tran_m); + + // // decomposition for measurement covariance (scalar case) + // float R_chol = sqrtf(R_iter); + // // construct H matrix + // // X_state updates in each iteration + // float x_iter = X_state[KC_STATE_X], y_iter = X_state[KC_STATE_Y], z_iter = X_state[KC_STATE_Z]; + // dx = x_iter - d->x; dy = y_iter - d->y; dz = z_iter - d->z; + + // float predicted_iter = arm_sqrt(powf(dx, 2) + powf(dy, 2) + powf(dz, 2)); + // // innovation term based on x_check + // float error_iter = measuredDistance - predicted_iter; + + // float e_y = error_iter; + + // if (predicted_iter != 0.0f) { + // // The measurement is: z = sqrt(dx^2 + dy^2 + dz^2). The derivative dz/dX gives h. + // h[KC_STATE_X] = dx/predicted_iter; + // h[KC_STATE_Y] = dy/predicted_iter; + // h[KC_STATE_Z] = dz/predicted_iter; + + // } else { + // // Avoid divide by zero + // h[KC_STATE_X] = 1.0f; + // h[KC_STATE_Y] = 0.0f; + // h[KC_STATE_Z] = 0.0f; + // } + // // check the measurement noise + // if (fabsf(R_chol - 0.0f) < 0.0001f){ + // e_y = error_iter / 0.0001f; + // } + // else{ + // e_y = error_iter / R_chol; + // } + // // Make sure P_chol, lower trangular matrix, is numerically stable + // for (int col=0; col<KC_STATE_DIM; col++) { + // for (int row=col; row<KC_STATE_DIM; row++) { + // if (isnan(P_chol[row][col]) || P_chol[row][col] > UPPER_BOUND) { + // P_chol[row][col] = UPPER_BOUND; + // } else if(row!=col && P_chol[row][col] < LOWER_BOUND){ + // P_chol[row][col] = LOWER_BOUND; + // } else if(row==col && P_chol[row][col]<0.0f){ + // P_chol[row][col] = 0.0f; + // } + // } + // } + // // Matrix inversion is numerically sensitive. + // // Add small values on the diagonal of P_chol to avoid numerical problems. + // float dummy_value = 1e-9f; + // for (int k=0; k<KC_STATE_DIM; k++){ + // P_chol[k][k] = P_chol[k][k] + dummy_value; + // } + // // keep P_chol + // matrixcopy(KC_STATE_DIM, KC_STATE_DIM, tmp1, P_chol); + // mat_inv(&tmp1m, &Pc_inv_m); // Pc_inv_m = inv(Pc_m) = inv(P_chol) + // mat_mult(&Pc_inv_m, &x_errm, &e_x_m); // e_x_m = Pc_inv_m.dot(x_errm) + + // // compute w_x, w_y --> weighting matrix + // // Since w_x is diagnal matrix, directly compute the inverse + // for (int state_k = 0; state_k < KC_STATE_DIM; state_k++){ + // GM_state(e_x[state_k], &wx_inv[state_k][state_k]); + // wx_inv[state_k][state_k] = (float)1.0 / wx_inv[state_k][state_k]; + // } + + // // rescale covariance matrix P + // mat_mult(&Pc_m, &wx_invm, &Pc_w_invm); // Pc_w_invm = P_chol.dot(linalg.inv(w_x)) + // mat_mult(&Pc_w_invm, &Pc_tran_m, &P_w_m); // P_w_m = Pc_w_invm.dot(Pc_tran_m) = P_chol.dot(linalg.inv(w_x)).dot(P_chol.T) + + // // rescale R matrix + // float w_y=0.0; float R_w = 0.0f; + // GM_UWB(e_y, &w_y); // compute the weighted measurement error: w_y + // if (fabsf(w_y - 0.0f) < 0.0001f){ + // R_w = (R_chol * R_chol) / 0.0001f; + // } + // else{ + // R_w = (R_chol * R_chol) / w_y; + // } + // // ====== INNOVATION COVARIANCE ====== // + + // mat_trans(&H, &HTm); + // mat_mult(&P_w_m, &HTm, &PHTm); // PHTm = P_w.dot(H.T). The P is the updated P_w + + // float HPHR = R_w; // HPH' + R. The R is the updated R_w + // for (int i=0; i<KC_STATE_DIM; i++) { // Add the element of HPH' to the above + // HPHR += h[i]*PHTd[i]; // this only works if the update is scalar (as in this function) + // } + // // ====== MEASUREMENT UPDATE ====== + // // Calculate the Kalman gain and perform the state update + // for (int i=0; i<KC_STATE_DIM; i++) { + // Kw[i] = PHTd[i]/HPHR; // rescaled kalman gain = (PH' (HPH' + R )^-1) with the updated P_w and R_w + // //[Note]: The error_check here is the innovation term based on x_check, which doesn't change during iterations. + // x_err[i] = Kw[i] * error_check; // error state for next iteration + // X_state[i] = this->S[i] + x_err[i]; // convert to nominal state + // } + // // update P_iter matrix and R matrix for next iteration + // matrixcopy(KC_STATE_DIM, KC_STATE_DIM, P_iter, P_w); + // R_iter = R_w; + // } + + + // // After n iterations, we obtain the rescaled (1) P = P_iter, (2) R = R_iter, (3) Kw. + // // Call the kalman update function with weighted P, weighted K, h, and error_check + // kalmanCoreUpdateWithPKE(this, &H, &Kwm, &P_w_m, error_check); } \ No newline at end of file diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_flow.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_flow.c index fb692d212..3f4aeb705 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_flow.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_flow.c @@ -34,69 +34,70 @@ static float measuredNY; void kalmanCoreUpdateWithFlow(kalmanCoreData_t* this, const flowMeasurement_t *flow, const Axis3f *gyro) { - // Inclusion of flow measurements in the EKF done by two scalar updates - - // ~~~ Camera constants ~~~ - // The angle of aperture is guessed from the raw data register and thankfully look to be symmetric - float Npix = 30.0; // [pixels] (same in x and y) - //float thetapix = DEG_TO_RAD * 4.0f; // [rad] (same in x and y) - float thetapix = DEG_TO_RAD * 4.2f; - //~~~ Body rates ~~~ - // TODO check if this is feasible or if some filtering has to be done - float omegax_b = gyro->x * DEG_TO_RAD; - float omegay_b = gyro->y * DEG_TO_RAD; - - // ~~~ Moves the body velocity into the global coordinate system ~~~ - // [bar{x},bar{y},bar{z}]_G = R*[bar{x},bar{y},bar{z}]_B - // - // \dot{x}_G = (R^T*[dot{x}_B,dot{y}_B,dot{z}_B])\dot \hat{x}_G - // \dot{x}_G = (R^T*[dot{x}_B,dot{y}_B,dot{z}_B])\dot \hat{x}_G - // - // where \hat{} denotes a basis vector, \dot{} denotes a derivative and - // _G and _B refer to the global/body coordinate systems. - - // Modification 1 - //dx_g = R[0][0] * S[KC_STATE_PX] + R[0][1] * S[KC_STATE_PY] + R[0][2] * S[KC_STATE_PZ]; - //dy_g = R[1][0] * S[KC_STATE_PX] + R[1][1] * S[KC_STATE_PY] + R[1][2] * S[KC_STATE_PZ]; - - - float dx_g = this->S[KC_STATE_PX]; - float dy_g = this->S[KC_STATE_PY]; - float z_g = 0.0; - // Saturate elevation in prediction and correction to avoid singularities - if ( this->S[KC_STATE_Z] < 0.1f ) { - z_g = 0.1; - } else { - z_g = this->S[KC_STATE_Z]; - } - - // ~~~ X velocity prediction and update ~~~ - // predics the number of accumulated pixels in the x-direction - float omegaFactor = 1.25f; - float hx[KC_STATE_DIM] = {0}; - arm_matrix_instance_f32 Hx = {1, KC_STATE_DIM, hx}; - predictedNX = (flow->dt * Npix / thetapix ) * ((dx_g * this->R[2][2] / z_g) - omegaFactor * omegay_b); - measuredNX = flow->dpixelx; - - // derive measurement equation with respect to dx (and z?) - hx[KC_STATE_Z] = (Npix * flow->dt / thetapix) * ((this->R[2][2] * dx_g) / (-z_g * z_g)); - hx[KC_STATE_PX] = (Npix * flow->dt / thetapix) * (this->R[2][2] / z_g); - - //First update - kalmanCoreScalarUpdate(this, &Hx, measuredNX-predictedNX, flow->stdDevX); - - // ~~~ Y velocity prediction and update ~~~ - float hy[KC_STATE_DIM] = {0}; - arm_matrix_instance_f32 Hy = {1, KC_STATE_DIM, hy}; - predictedNY = (flow->dt * Npix / thetapix ) * ((dy_g * this->R[2][2] / z_g) + omegaFactor * omegax_b); - measuredNY = flow->dpixely; - - // derive measurement equation with respect to dy (and z?) - hy[KC_STATE_Z] = (Npix * flow->dt / thetapix) * ((this->R[2][2] * dy_g) / (-z_g * z_g)); - hy[KC_STATE_PY] = (Npix * flow->dt / thetapix) * (this->R[2][2] / z_g); - - // Second update - kalmanCoreScalarUpdate(this, &Hy, measuredNY-predictedNY, flow->stdDevY); + //COMMENTED FIRMWARE +// // Inclusion of flow measurements in the EKF done by two scalar updates + +// // ~~~ Camera constants ~~~ +// // The angle of aperture is guessed from the raw data register and thankfully look to be symmetric +// float Npix = 30.0; // [pixels] (same in x and y) +// //float thetapix = DEG_TO_RAD * 4.0f; // [rad] (same in x and y) +// float thetapix = DEG_TO_RAD * 4.2f; +// //~~~ Body rates ~~~ +// // TODO check if this is feasible or if some filtering has to be done +// float omegax_b = gyro->x * DEG_TO_RAD; +// float omegay_b = gyro->y * DEG_TO_RAD; + +// // ~~~ Moves the body velocity into the global coordinate system ~~~ +// // [bar{x},bar{y},bar{z}]_G = R*[bar{x},bar{y},bar{z}]_B +// // +// // \dot{x}_G = (R^T*[dot{x}_B,dot{y}_B,dot{z}_B])\dot \hat{x}_G +// // \dot{x}_G = (R^T*[dot{x}_B,dot{y}_B,dot{z}_B])\dot \hat{x}_G +// // +// // where \hat{} denotes a basis vector, \dot{} denotes a derivative and +// // _G and _B refer to the global/body coordinate systems. + +// // Modification 1 +// //dx_g = R[0][0] * S[KC_STATE_PX] + R[0][1] * S[KC_STATE_PY] + R[0][2] * S[KC_STATE_PZ]; +// //dy_g = R[1][0] * S[KC_STATE_PX] + R[1][1] * S[KC_STATE_PY] + R[1][2] * S[KC_STATE_PZ]; + + +// float dx_g = this->S[KC_STATE_PX]; +// float dy_g = this->S[KC_STATE_PY]; +// float z_g = 0.0; +// // Saturate elevation in prediction and correction to avoid singularities +// if ( this->S[KC_STATE_Z] < 0.1f ) { +// z_g = 0.1; +// } else { +// z_g = this->S[KC_STATE_Z]; +// } + +// // ~~~ X velocity prediction and update ~~~ +// // predics the number of accumulated pixels in the x-direction +// float omegaFactor = 1.25f; +// float hx[KC_STATE_DIM] = {0}; +// arm_matrix_instance_f32 Hx = {1, KC_STATE_DIM, hx}; +// predictedNX = (flow->dt * Npix / thetapix ) * ((dx_g * this->R[2][2] / z_g) - omegaFactor * omegay_b); +// measuredNX = flow->dpixelx; + +// // derive measurement equation with respect to dx (and z?) +// hx[KC_STATE_Z] = (Npix * flow->dt / thetapix) * ((this->R[2][2] * dx_g) / (-z_g * z_g)); +// hx[KC_STATE_PX] = (Npix * flow->dt / thetapix) * (this->R[2][2] / z_g); + +// //First update +// kalmanCoreScalarUpdate(this, &Hx, measuredNX-predictedNX, flow->stdDevX); + +// // ~~~ Y velocity prediction and update ~~~ +// float hy[KC_STATE_DIM] = {0}; +// arm_matrix_instance_f32 Hy = {1, KC_STATE_DIM, hy}; +// predictedNY = (flow->dt * Npix / thetapix ) * ((dy_g * this->R[2][2] / z_g) + omegaFactor * omegax_b); +// measuredNY = flow->dpixely; + +// // derive measurement equation with respect to dy (and z?) +// hy[KC_STATE_Z] = (Npix * flow->dt / thetapix) * ((this->R[2][2] * dy_g) / (-z_g * z_g)); +// hy[KC_STATE_PY] = (Npix * flow->dt / thetapix) * (this->R[2][2] / z_g); + +// // Second update +// kalmanCoreScalarUpdate(this, &Hy, measuredNY-predictedNY, flow->stdDevY); } /** diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_pose.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_pose.c index 4f1fc7fbb..6b17370ef 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_pose.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_pose.c @@ -30,33 +30,34 @@ void kalmanCoreUpdateWithPose(kalmanCoreData_t* this, poseMeasurement_t *pose) { // a direct measurement of states x, y, and z, and orientation // do a scalar update for each state, since this should be faster than updating all together - for (int i=0; i<3; i++) { - float h[KC_STATE_DIM] = {0}; - arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; - h[KC_STATE_X+i] = 1; - kalmanCoreScalarUpdate(this, &H, pose->pos[i] - this->S[KC_STATE_X+i], pose->stdDevPos); - } + //COMMENTED FIRMWARE + // for (int i=0; i<3; i++) { + // float h[KC_STATE_DIM] = {0}; + // arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; + // h[KC_STATE_X+i] = 1; + // kalmanCoreScalarUpdate(this, &H, pose->pos[i] - this->S[KC_STATE_X+i], pose->stdDevPos); + // } - // compute orientation error - struct quat const q_ekf = mkquat(this->q[1], this->q[2], this->q[3], this->q[0]); - struct quat const q_measured = mkquat(pose->quat.x, pose->quat.y, pose->quat.z, pose->quat.w); - struct quat const q_residual = qqmul(qinv(q_ekf), q_measured); - // small angle approximation, see eq. 141 in http://mars.cs.umn.edu/tr/reports/Trawny05b.pdf - struct vec const err_quat = vscl(2.0f / q_residual.w, quatimagpart(q_residual)); + // // compute orientation error + // struct quat const q_ekf = mkquat(this->q[1], this->q[2], this->q[3], this->q[0]); + // struct quat const q_measured = mkquat(pose->quat.x, pose->quat.y, pose->quat.z, pose->quat.w); + // struct quat const q_residual = qqmul(qinv(q_ekf), q_measured); + // // small angle approximation, see eq. 141 in http://mars.cs.umn.edu/tr/reports/Trawny05b.pdf + // struct vec const err_quat = vscl(2.0f / q_residual.w, quatimagpart(q_residual)); - // do a scalar update for each state - { - float h[KC_STATE_DIM] = {0}; - arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; - h[KC_STATE_D0] = 1; - kalmanCoreScalarUpdate(this, &H, err_quat.x, pose->stdDevQuat); - h[KC_STATE_D0] = 0; + // // do a scalar update for each state + // { + // float h[KC_STATE_DIM] = {0}; + // arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; + // h[KC_STATE_D0] = 1; + // kalmanCoreScalarUpdate(this, &H, err_quat.x, pose->stdDevQuat); + // h[KC_STATE_D0] = 0; - h[KC_STATE_D1] = 1; - kalmanCoreScalarUpdate(this, &H, err_quat.y, pose->stdDevQuat); - h[KC_STATE_D1] = 0; + // h[KC_STATE_D1] = 1; + // kalmanCoreScalarUpdate(this, &H, err_quat.y, pose->stdDevQuat); + // h[KC_STATE_D1] = 0; - h[KC_STATE_D2] = 1; - kalmanCoreScalarUpdate(this, &H, err_quat.z, pose->stdDevQuat); - } + // h[KC_STATE_D2] = 1; + // kalmanCoreScalarUpdate(this, &H, err_quat.z, pose->stdDevQuat); + // } } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_position.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_position.c index cae521958..0d20ddb8c 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_position.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_position.c @@ -29,10 +29,11 @@ void kalmanCoreUpdateWithPosition(kalmanCoreData_t* this, positionMeasurement_t { // a direct measurement of states x, y, and z // do a scalar update for each state, since this should be faster than updating all together - for (int i=0; i<3; i++) { - float h[KC_STATE_DIM] = {0}; - arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; - h[KC_STATE_X+i] = 1; - kalmanCoreScalarUpdate(this, &H, xyz->pos[i] - this->S[KC_STATE_X+i], xyz->stdDev); - } + //COMMENTED FIRMWARE + // for (int i=0; i<3; i++) { + // float h[KC_STATE_DIM] = {0}; + // arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; + // h[KC_STATE_X+i] = 1; + // kalmanCoreScalarUpdate(this, &H, xyz->pos[i] - this->S[KC_STATE_X+i], xyz->stdDev); + // } } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_sweep_angles.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_sweep_angles.c index 17c0aae93..e295eb46e 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_sweep_angles.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_sweep_angles.c @@ -28,67 +28,68 @@ void kalmanCoreUpdateWithSweepAngles(kalmanCoreData_t *this, sweepAngleMeasurement_t *sweepInfo, const uint32_t tick, OutlierFilterLhState_t* sweepOutlierFilterState) { - // Rotate the sensor position from CF reference frame to global reference frame, - // using the CF roatation matrix - vec3d s; - arm_matrix_instance_f32 Rcf_ = {3, 3, (float32_t *)this->R}; - arm_matrix_instance_f32 scf_ = {3, 1, (float32_t *)*sweepInfo->sensorPos}; - arm_matrix_instance_f32 s_ = {3, 1, s}; - mat_mult(&Rcf_, &scf_, &s_); + //COMMENTED FIRMWARE + // // Rotate the sensor position from CF reference frame to global reference frame, + // // using the CF roatation matrix + // vec3d s; + // arm_matrix_instance_f32 Rcf_ = {3, 3, (float32_t *)this->R}; + // arm_matrix_instance_f32 scf_ = {3, 1, (float32_t *)*sweepInfo->sensorPos}; + // arm_matrix_instance_f32 s_ = {3, 1, s}; + // mat_mult(&Rcf_, &scf_, &s_); - // Get the current state values of the position of the crazyflie (global reference frame) and add the relative sensor pos - vec3d pcf = {this->S[KC_STATE_X] + s[0], this->S[KC_STATE_Y] + s[1], this->S[KC_STATE_Z] + s[2]}; + // // Get the current state values of the position of the crazyflie (global reference frame) and add the relative sensor pos + // vec3d pcf = {this->S[KC_STATE_X] + s[0], this->S[KC_STATE_Y] + s[1], this->S[KC_STATE_Z] + s[2]}; - // Calculate the difference between the rotor and the sensor on the CF (global reference frame) - const vec3d* pr = sweepInfo->rotorPos; - vec3d stmp = {pcf[0] - (*pr)[0], pcf[1] - (*pr)[1], pcf[2] - (*pr)[2]}; - arm_matrix_instance_f32 stmp_ = {3, 1, stmp}; + // // Calculate the difference between the rotor and the sensor on the CF (global reference frame) + // const vec3d* pr = sweepInfo->rotorPos; + // vec3d stmp = {pcf[0] - (*pr)[0], pcf[1] - (*pr)[1], pcf[2] - (*pr)[2]}; + // arm_matrix_instance_f32 stmp_ = {3, 1, stmp}; - // Rotate the difference in position to the rotor reference frame, - // using the rotor inverse rotation matrix - vec3d sr; - arm_matrix_instance_f32 Rr_inv_ = {3, 3, (float32_t *)(*sweepInfo->rotorRotInv)}; - arm_matrix_instance_f32 sr_ = {3, 1, sr}; - mat_mult(&Rr_inv_, &stmp_, &sr_); + // // Rotate the difference in position to the rotor reference frame, + // // using the rotor inverse rotation matrix + // vec3d sr; + // arm_matrix_instance_f32 Rr_inv_ = {3, 3, (float32_t *)(*sweepInfo->rotorRotInv)}; + // arm_matrix_instance_f32 sr_ = {3, 1, sr}; + // mat_mult(&Rr_inv_, &stmp_, &sr_); - // The following computations are in the rotor refernece frame - const float x = sr[0]; - const float y = sr[1]; - const float z = sr[2]; - const float t = sweepInfo->t; - const float tan_t = tanf(t); + // // The following computations are in the rotor refernece frame + // const float x = sr[0]; + // const float y = sr[1]; + // const float z = sr[2]; + // const float t = sweepInfo->t; + // const float tan_t = tanf(t); - const float r2 = x * x + y * y; - const float r = arm_sqrt(r2); + // const float r2 = x * x + y * y; + // const float r = arm_sqrt(r2); - const float predictedSweepAngle = sweepInfo->calibrationMeasurementModel(x, y, z, t, sweepInfo->calib); - const float measuredSweepAngle = sweepInfo->measuredSweepAngle; - const float error = measuredSweepAngle - predictedSweepAngle; + // const float predictedSweepAngle = sweepInfo->calibrationMeasurementModel(x, y, z, t, sweepInfo->calib); + // const float measuredSweepAngle = sweepInfo->measuredSweepAngle; + // const float error = measuredSweepAngle - predictedSweepAngle; - if (outlierFilterValidateLighthouseSweep(sweepOutlierFilterState, r, error, tick)) { - // Calculate H vector (in the rotor reference frame) - const float z_tan_t = z * tan_t; - const float qNum = r2 - z_tan_t * z_tan_t; - // Avoid singularity - if (qNum > 0.0001f) { - const float q = tan_t / arm_sqrt(qNum); - vec3d gr = {(-y - x * z * q) / r2, (x - y * z * q) / r2 , q}; + // if (outlierFilterValidateLighthouseSweep(sweepOutlierFilterState, r, error, tick)) { + // // Calculate H vector (in the rotor reference frame) + // const float z_tan_t = z * tan_t; + // const float qNum = r2 - z_tan_t * z_tan_t; + // // Avoid singularity + // if (qNum > 0.0001f) { + // const float q = tan_t / arm_sqrt(qNum); + // vec3d gr = {(-y - x * z * q) / r2, (x - y * z * q) / r2 , q}; - // gr is in the rotor reference frame, rotate back to the global - // reference frame using the rotor rotation matrix - vec3d g; - arm_matrix_instance_f32 gr_ = {3, 1, gr}; - arm_matrix_instance_f32 Rr_ = {3, 3, (float32_t *)(*sweepInfo->rotorRot)}; - arm_matrix_instance_f32 g_ = {3, 1, g}; - mat_mult(&Rr_, &gr_, &g_); + // // gr is in the rotor reference frame, rotate back to the global + // // reference frame using the rotor rotation matrix + // vec3d g; + // arm_matrix_instance_f32 gr_ = {3, 1, gr}; + // arm_matrix_instance_f32 Rr_ = {3, 3, (float32_t *)(*sweepInfo->rotorRot)}; + // arm_matrix_instance_f32 g_ = {3, 1, g}; + // mat_mult(&Rr_, &gr_, &g_); - float h[KC_STATE_DIM] = {0}; - h[KC_STATE_X] = g[0]; - h[KC_STATE_Y] = g[1]; - h[KC_STATE_Z] = g[2]; + // float h[KC_STATE_DIM] = {0}; + // h[KC_STATE_X] = g[0]; + // h[KC_STATE_Y] = g[1]; + // h[KC_STATE_Z] = g[2]; - arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; - kalmanCoreScalarUpdate(this, &H, error, sweepInfo->stdDev); - } - } + // arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; + // kalmanCoreScalarUpdate(this, &H, error, sweepInfo->stdDev); + // } + // } } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_tdoa.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_tdoa.c index 761e0e4b0..46f7e17c5 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_tdoa.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_tdoa.c @@ -32,63 +32,64 @@ TESTABLE_STATIC uint32_t tdoaCount = 0; void kalmanCoreUpdateWithTDOA(kalmanCoreData_t* this, tdoaMeasurement_t *tdoa) { - if (tdoaCount >= 100) - { - /** - * Measurement equation: - * dR = dT + d1 - d0 - */ - - float measurement = tdoa->distanceDiff; - - // predict based on current state - float x = this->S[KC_STATE_X]; - float y = this->S[KC_STATE_Y]; - float z = this->S[KC_STATE_Z]; - - float x1 = tdoa->anchorPositions[1].x, y1 = tdoa->anchorPositions[1].y, z1 = tdoa->anchorPositions[1].z; - float x0 = tdoa->anchorPositions[0].x, y0 = tdoa->anchorPositions[0].y, z0 = tdoa->anchorPositions[0].z; - - float dx1 = x - x1; - float dy1 = y - y1; - float dz1 = z - z1; - - float dy0 = y - y0; - float dx0 = x - x0; - float dz0 = z - z0; - - float d1 = sqrtf(powf(dx1, 2) + powf(dy1, 2) + powf(dz1, 2)); - float d0 = sqrtf(powf(dx0, 2) + powf(dy0, 2) + powf(dz0, 2)); - - float predicted = d1 - d0; - float error = measurement - predicted; - - float h[KC_STATE_DIM] = {0}; - arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; - - if ((d0 != 0.0f) && (d1 != 0.0f)) { - h[KC_STATE_X] = (dx1 / d1 - dx0 / d0); - h[KC_STATE_Y] = (dy1 / d1 - dy0 / d0); - h[KC_STATE_Z] = (dz1 / d1 - dz0 / d0); - - vector_t jacobian = { - .x = h[KC_STATE_X], - .y = h[KC_STATE_Y], - .z = h[KC_STATE_Z], - }; - - point_t estimatedPosition = { - .x = this->S[KC_STATE_X], - .y = this->S[KC_STATE_Y], - .z = this->S[KC_STATE_Z], - }; - - bool sampleIsGood = outlierFilterValidateTdoaSteps(tdoa, error, &jacobian, &estimatedPosition); - if (sampleIsGood) { - kalmanCoreScalarUpdate(this, &H, error, tdoa->stdDev); - } - } - } - - tdoaCount++; + //COMMENTED FIRMWARE + // if (tdoaCount >= 100) + // { + // /** + // * Measurement equation: + // * dR = dT + d1 - d0 + // */ + + // float measurement = tdoa->distanceDiff; + + // // predict based on current state + // float x = this->S[KC_STATE_X]; + // float y = this->S[KC_STATE_Y]; + // float z = this->S[KC_STATE_Z]; + + // float x1 = tdoa->anchorPositions[1].x, y1 = tdoa->anchorPositions[1].y, z1 = tdoa->anchorPositions[1].z; + // float x0 = tdoa->anchorPositions[0].x, y0 = tdoa->anchorPositions[0].y, z0 = tdoa->anchorPositions[0].z; + + // float dx1 = x - x1; + // float dy1 = y - y1; + // float dz1 = z - z1; + + // float dy0 = y - y0; + // float dx0 = x - x0; + // float dz0 = z - z0; + + // float d1 = sqrtf(powf(dx1, 2) + powf(dy1, 2) + powf(dz1, 2)); + // float d0 = sqrtf(powf(dx0, 2) + powf(dy0, 2) + powf(dz0, 2)); + + // float predicted = d1 - d0; + // float error = measurement - predicted; + + // float h[KC_STATE_DIM] = {0}; + // arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; + + // if ((d0 != 0.0f) && (d1 != 0.0f)) { + // h[KC_STATE_X] = (dx1 / d1 - dx0 / d0); + // h[KC_STATE_Y] = (dy1 / d1 - dy0 / d0); + // h[KC_STATE_Z] = (dz1 / d1 - dz0 / d0); + + // vector_t jacobian = { + // .x = h[KC_STATE_X], + // .y = h[KC_STATE_Y], + // .z = h[KC_STATE_Z], + // }; + + // point_t estimatedPosition = { + // .x = this->S[KC_STATE_X], + // .y = this->S[KC_STATE_Y], + // .z = this->S[KC_STATE_Z], + // }; + + // bool sampleIsGood = outlierFilterValidateTdoaSteps(tdoa, error, &jacobian, &estimatedPosition); + // if (sampleIsGood) { + // kalmanCoreScalarUpdate(this, &H, error, tdoa->stdDev); + // } + // } + // } + + // tdoaCount++; } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_tdoa_robust.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_tdoa_robust.c index bd6f15caf..13d31dcdb 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_tdoa_robust.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_tdoa_robust.c @@ -65,174 +65,175 @@ static void GM_state(float e, float * GM_e){ // robsut update function void kalmanCoreRobustUpdateWithTDOA(kalmanCoreData_t* this, tdoaMeasurement_t *tdoa) { - // Measurement equation: - // d_ij = d_j - d_i - float measurement = 0.0f; - float x = this->S[KC_STATE_X]; - float y = this->S[KC_STATE_Y]; - float z = this->S[KC_STATE_Z]; - - float x1 = tdoa->anchorPositions[1].x, y1 = tdoa->anchorPositions[1].y, z1 = tdoa->anchorPositions[1].z; - float x0 = tdoa->anchorPositions[0].x, y0 = tdoa->anchorPositions[0].y, z0 = tdoa->anchorPositions[0].z; - - float dx1 = x - x1; float dy1 = y - y1; float dz1 = z - z1; - float dx0 = x - x0; float dy0 = y - y0; float dz0 = z - z0; - - float d1 = sqrtf(powf(dx1, 2) + powf(dy1, 2) + powf(dz1, 2)); - float d0 = sqrtf(powf(dx0, 2) + powf(dy0, 2) + powf(dz0, 2)); - // if measurements make sense - if ((d0 != 0.0f) && (d1 != 0.0f)) { - float predicted = d1 - d0; - measurement = tdoa->distanceDiff; + //COMMENTED FIRMWARE + // // Measurement equation: + // // d_ij = d_j - d_i + // float measurement = 0.0f; + // float x = this->S[KC_STATE_X]; + // float y = this->S[KC_STATE_Y]; + // float z = this->S[KC_STATE_Z]; + + // float x1 = tdoa->anchorPositions[1].x, y1 = tdoa->anchorPositions[1].y, z1 = tdoa->anchorPositions[1].z; + // float x0 = tdoa->anchorPositions[0].x, y0 = tdoa->anchorPositions[0].y, z0 = tdoa->anchorPositions[0].z; + + // float dx1 = x - x1; float dy1 = y - y1; float dz1 = z - z1; + // float dx0 = x - x0; float dy0 = y - y0; float dz0 = z - z0; + + // float d1 = sqrtf(powf(dx1, 2) + powf(dy1, 2) + powf(dz1, 2)); + // float d0 = sqrtf(powf(dx0, 2) + powf(dy0, 2) + powf(dz0, 2)); + // // if measurements make sense + // if ((d0 != 0.0f) && (d1 != 0.0f)) { + // float predicted = d1 - d0; + // measurement = tdoa->distanceDiff; - // innovation term based on prior x - float error_check = measurement - predicted; // innovation term based on prior state - // ---------------------- matrix defination ----------------------------- // - static float P_chol[KC_STATE_DIM][KC_STATE_DIM]; - static arm_matrix_instance_f32 Pc_m = {KC_STATE_DIM, KC_STATE_DIM, (float *)P_chol}; - static float Pc_tran[KC_STATE_DIM][KC_STATE_DIM]; - static arm_matrix_instance_f32 Pc_tran_m = {KC_STATE_DIM, KC_STATE_DIM, (float *)Pc_tran}; - - float h[KC_STATE_DIM] = {0}; - arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; - // The Kalman gain as a column vector - static float Kw[KC_STATE_DIM]; - static arm_matrix_instance_f32 Kwm = {KC_STATE_DIM, 1, (float *)Kw}; + // // innovation term based on prior x + // float error_check = measurement - predicted; // innovation term based on prior state + // // ---------------------- matrix defination ----------------------------- // + // static float P_chol[KC_STATE_DIM][KC_STATE_DIM]; + // static arm_matrix_instance_f32 Pc_m = {KC_STATE_DIM, KC_STATE_DIM, (float *)P_chol}; + // static float Pc_tran[KC_STATE_DIM][KC_STATE_DIM]; + // static arm_matrix_instance_f32 Pc_tran_m = {KC_STATE_DIM, KC_STATE_DIM, (float *)Pc_tran}; + + // float h[KC_STATE_DIM] = {0}; + // arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; + // // The Kalman gain as a column vector + // static float Kw[KC_STATE_DIM]; + // static arm_matrix_instance_f32 Kwm = {KC_STATE_DIM, 1, (float *)Kw}; - static float e_x[KC_STATE_DIM]; - static arm_matrix_instance_f32 e_x_m = {KC_STATE_DIM, 1, e_x}; + // static float e_x[KC_STATE_DIM]; + // static arm_matrix_instance_f32 e_x_m = {KC_STATE_DIM, 1, e_x}; - static float Pc_inv[KC_STATE_DIM][KC_STATE_DIM]; - static arm_matrix_instance_f32 Pc_inv_m = {KC_STATE_DIM, KC_STATE_DIM, (float *)Pc_inv}; + // static float Pc_inv[KC_STATE_DIM][KC_STATE_DIM]; + // static arm_matrix_instance_f32 Pc_inv_m = {KC_STATE_DIM, KC_STATE_DIM, (float *)Pc_inv}; - // rescale matrix - static float wx_inv[KC_STATE_DIM][KC_STATE_DIM]; - static arm_matrix_instance_f32 wx_invm = {KC_STATE_DIM, KC_STATE_DIM, (float *)wx_inv}; - // tmp matrix for P_chol inverse - static float tmp1[KC_STATE_DIM][KC_STATE_DIM]; - static arm_matrix_instance_f32 tmp1m = {KC_STATE_DIM, KC_STATE_DIM, (float *)tmp1}; - - static float Pc_w_inv[KC_STATE_DIM][KC_STATE_DIM]; - static arm_matrix_instance_f32 Pc_w_invm = {KC_STATE_DIM, KC_STATE_DIM, (float *)Pc_w_inv}; - - static float P_w[KC_STATE_DIM][KC_STATE_DIM]; - static arm_matrix_instance_f32 P_w_m = {KC_STATE_DIM, KC_STATE_DIM, (float *)P_w}; - - static float HTd[KC_STATE_DIM]; - static arm_matrix_instance_f32 HTm = {KC_STATE_DIM, 1, HTd}; - - static float PHTd[KC_STATE_DIM]; - static arm_matrix_instance_f32 PHTm = {KC_STATE_DIM, 1, PHTd}; - // ------------------- Initialization -----------------------// - // x prior (error state), set to be zeros. Not used for error state Kalman filter. Provide here for completeness - // float xpr[STATE_DIM] = {0.0}; - - // x_err comes from the KF update is the state of error state Kalman filter, set to be zero initially - static float x_err[KC_STATE_DIM] = {0.0}; - static arm_matrix_instance_f32 x_errm = {KC_STATE_DIM, 1, x_err}; - static float X_state[KC_STATE_DIM] = {0.0}; - float P_iter[KC_STATE_DIM][KC_STATE_DIM]; - matrixcopy(KC_STATE_DIM, KC_STATE_DIM, P_iter,this->P); // init P_iter as P_prior + // // rescale matrix + // static float wx_inv[KC_STATE_DIM][KC_STATE_DIM]; + // static arm_matrix_instance_f32 wx_invm = {KC_STATE_DIM, KC_STATE_DIM, (float *)wx_inv}; + // // tmp matrix for P_chol inverse + // static float tmp1[KC_STATE_DIM][KC_STATE_DIM]; + // static arm_matrix_instance_f32 tmp1m = {KC_STATE_DIM, KC_STATE_DIM, (float *)tmp1}; + + // static float Pc_w_inv[KC_STATE_DIM][KC_STATE_DIM]; + // static arm_matrix_instance_f32 Pc_w_invm = {KC_STATE_DIM, KC_STATE_DIM, (float *)Pc_w_inv}; + + // static float P_w[KC_STATE_DIM][KC_STATE_DIM]; + // static arm_matrix_instance_f32 P_w_m = {KC_STATE_DIM, KC_STATE_DIM, (float *)P_w}; + + // static float HTd[KC_STATE_DIM]; + // static arm_matrix_instance_f32 HTm = {KC_STATE_DIM, 1, HTd}; + + // static float PHTd[KC_STATE_DIM]; + // static arm_matrix_instance_f32 PHTm = {KC_STATE_DIM, 1, PHTd}; + // // ------------------- Initialization -----------------------// + // // x prior (error state), set to be zeros. Not used for error state Kalman filter. Provide here for completeness + // // float xpr[STATE_DIM] = {0.0}; + + // // x_err comes from the KF update is the state of error state Kalman filter, set to be zero initially + // static float x_err[KC_STATE_DIM] = {0.0}; + // static arm_matrix_instance_f32 x_errm = {KC_STATE_DIM, 1, x_err}; + // static float X_state[KC_STATE_DIM] = {0.0}; + // float P_iter[KC_STATE_DIM][KC_STATE_DIM]; + // matrixcopy(KC_STATE_DIM, KC_STATE_DIM, P_iter,this->P); // init P_iter as P_prior - float R_iter = tdoa->stdDev * tdoa->stdDev; // measurement covariance - vectorcopy(KC_STATE_DIM, X_state, this->S); // copy Xpr to X_State and then update in each iterations - - // ---------------------- Start iteration ----------------------- // - for (int iter = 0; iter < MAX_ITER; iter++){ - // cholesky decomposition for the prior covariance matrix - Cholesky_Decomposition(KC_STATE_DIM, P_iter, P_chol); // P_chol is a lower triangular matrix - mat_trans(&Pc_m, &Pc_tran_m); - - // decomposition for measurement covariance (scalar case) - float R_chol = sqrtf(R_iter); - // construct H matrix - // X_state updates in each iteration - float x_iter = X_state[KC_STATE_X], y_iter = X_state[KC_STATE_Y], z_iter = X_state[KC_STATE_Z]; - - dx1 = x_iter - x1; dy1 = y_iter - y1; dz1 = z_iter - z1; - dx0 = x_iter - x0; dy0 = y_iter - y0; dz0 = z_iter - z0; - - d1 = sqrtf(powf(dx1, 2) + powf(dy1, 2) + powf(dz1, 2)); - d0 = sqrtf(powf(dx0, 2) + powf(dy0, 2) + powf(dz0, 2)); + // float R_iter = tdoa->stdDev * tdoa->stdDev; // measurement covariance + // vectorcopy(KC_STATE_DIM, X_state, this->S); // copy Xpr to X_State and then update in each iterations + + // // ---------------------- Start iteration ----------------------- // + // for (int iter = 0; iter < MAX_ITER; iter++){ + // // cholesky decomposition for the prior covariance matrix + // Cholesky_Decomposition(KC_STATE_DIM, P_iter, P_chol); // P_chol is a lower triangular matrix + // mat_trans(&Pc_m, &Pc_tran_m); + + // // decomposition for measurement covariance (scalar case) + // float R_chol = sqrtf(R_iter); + // // construct H matrix + // // X_state updates in each iteration + // float x_iter = X_state[KC_STATE_X], y_iter = X_state[KC_STATE_Y], z_iter = X_state[KC_STATE_Z]; + + // dx1 = x_iter - x1; dy1 = y_iter - y1; dz1 = z_iter - z1; + // dx0 = x_iter - x0; dy0 = y_iter - y0; dz0 = z_iter - z0; + + // d1 = sqrtf(powf(dx1, 2) + powf(dy1, 2) + powf(dz1, 2)); + // d0 = sqrtf(powf(dx0, 2) + powf(dy0, 2) + powf(dz0, 2)); - float predicted_iter = d1 - d0; // predicted measurements in each iteration based on X_state - float error_iter = measurement - predicted_iter; // innovation term based on iterated X_state - float e_y = error_iter; - if ((d0 != 0.0f) && (d1 != 0.0f)){ - // measurement Jacobian changes in each iteration w.r.t linearization point [x_iter, y_iter, z_iter] - h[KC_STATE_X] = (dx1 / d1 - dx0 / d0); - h[KC_STATE_Y] = (dy1 / d1 - dy0 / d0); - h[KC_STATE_Z] = (dz1 / d1 - dz0 / d0); - - if (fabsf(R_chol - 0.0f) < 0.0001f){ - e_y = error_iter / 0.0001f; - } - else{ - e_y = error_iter / R_chol; - } - // Make sure P_chol, lower trangular matrix, is numerically stable - for (int col=0; col<KC_STATE_DIM; col++) { - for (int row=col; row<KC_STATE_DIM; row++) { - if (isnan(P_chol[row][col]) || P_chol[row][col] > UPPER_BOUND) { - P_chol[row][col] = UPPER_BOUND; - } else if(row!=col && P_chol[row][col] < LOWER_BOUND){ - P_chol[row][col] = LOWER_BOUND; - } else if(row==col && P_chol[row][col]<0.0f){ - P_chol[row][col] = 0.0f; - } - } - } - // Matrix inversion is numerically sensitive. - // Add small values on the diagonal of P_chol to avoid numerical problems. - float dummy_value = 1e-9f; - for (int k=0; k<KC_STATE_DIM; k++){ - P_chol[k][k] = P_chol[k][k] + dummy_value; - } - // keep P_chol - matrixcopy(KC_STATE_DIM, KC_STATE_DIM, tmp1, P_chol); - mat_inv(&tmp1m, &Pc_inv_m); // Pc_inv_m = inv(Pc_m) = inv(P_chol) - mat_mult(&Pc_inv_m, &x_errm, &e_x_m); // e_x_m = Pc_inv_m.dot(x_errm) - // compute w_x, w_y --> weighting matrix - // Since w_x is diagnal matrix, compute the inverse directly - for (int state_k = 0; state_k < KC_STATE_DIM; state_k++){ - GM_state(e_x[state_k], &wx_inv[state_k][state_k]); - wx_inv[state_k][state_k] = (float)1.0 / wx_inv[state_k][state_k]; - } - // rescale covariance matrix P - mat_mult(&Pc_m, &wx_invm, &Pc_w_invm); // Pc_w_invm = P_chol.dot(linalg.inv(w_x)) - mat_mult(&Pc_w_invm, &Pc_tran_m, &P_w_m); // P_w_m = Pc_w_invm.dot(Pc_tran_m) = P_chol.dot(linalg.inv(w_x)).dot(P_chol.T) - // rescale R matrix - float w_y=0.0; float R_w = 0.0f; - GM_UWB(e_y, &w_y); // compute the weighted measurement error: w_y - if (fabsf(w_y - 0.0f) < 0.0001f){ - R_w = (R_chol * R_chol) / 0.0001f; - }else{ - R_w = (R_chol * R_chol) / w_y; - } - // ====== INNOVATION COVARIANCE ====== // - mat_trans(&H, &HTm); - mat_mult(&P_w_m, &HTm, &PHTm); // PHTm = P_w.dot(H.T). The P is the updated P_w - - float HPHR = R_w; // HPH' + R. The R is the updated R_w - for (int i=0; i<KC_STATE_DIM; i++) { // Add the element of HPH' to the above - HPHR += h[i]*PHTd[i]; // this only works if the update is scalar (as in this function) - } - // ====== MEASUREMENT UPDATE ====== - // Calculate the Kalman gain and perform the state update - for (int i=0; i<KC_STATE_DIM; i++) { - Kw[i] = PHTd[i]/HPHR; // rescaled kalman gain = (PH' (HPH' + R )^-1) with the updated P_w and R_w - //[Note]: The error_check here is the innovation term based on prior state, which doesn't change during iterations. - x_err[i] = Kw[i] * error_check; // error state for next iteration - X_state[i] = this->S[i] + x_err[i]; // convert to nominal state - } - // update P_iter matrix and R matrix for next iteration - matrixcopy(KC_STATE_DIM, KC_STATE_DIM, P_iter, P_w); - R_iter = R_w; - } - } - // After n iterations, we obtain the rescaled (1) P = P_iter, (2) R = R_iter, (3) Kw. - // Call the kalman update function with weighted P, weighted K, h, and error_check - kalmanCoreUpdateWithPKE(this, &H, &Kwm, &P_w_m, error_check); - - } + // float predicted_iter = d1 - d0; // predicted measurements in each iteration based on X_state + // float error_iter = measurement - predicted_iter; // innovation term based on iterated X_state + // float e_y = error_iter; + // if ((d0 != 0.0f) && (d1 != 0.0f)){ + // // measurement Jacobian changes in each iteration w.r.t linearization point [x_iter, y_iter, z_iter] + // h[KC_STATE_X] = (dx1 / d1 - dx0 / d0); + // h[KC_STATE_Y] = (dy1 / d1 - dy0 / d0); + // h[KC_STATE_Z] = (dz1 / d1 - dz0 / d0); + + // if (fabsf(R_chol - 0.0f) < 0.0001f){ + // e_y = error_iter / 0.0001f; + // } + // else{ + // e_y = error_iter / R_chol; + // } + // // Make sure P_chol, lower trangular matrix, is numerically stable + // for (int col=0; col<KC_STATE_DIM; col++) { + // for (int row=col; row<KC_STATE_DIM; row++) { + // if (isnan(P_chol[row][col]) || P_chol[row][col] > UPPER_BOUND) { + // P_chol[row][col] = UPPER_BOUND; + // } else if(row!=col && P_chol[row][col] < LOWER_BOUND){ + // P_chol[row][col] = LOWER_BOUND; + // } else if(row==col && P_chol[row][col]<0.0f){ + // P_chol[row][col] = 0.0f; + // } + // } + // } + // // Matrix inversion is numerically sensitive. + // // Add small values on the diagonal of P_chol to avoid numerical problems. + // float dummy_value = 1e-9f; + // for (int k=0; k<KC_STATE_DIM; k++){ + // P_chol[k][k] = P_chol[k][k] + dummy_value; + // } + // // keep P_chol + // matrixcopy(KC_STATE_DIM, KC_STATE_DIM, tmp1, P_chol); + // mat_inv(&tmp1m, &Pc_inv_m); // Pc_inv_m = inv(Pc_m) = inv(P_chol) + // mat_mult(&Pc_inv_m, &x_errm, &e_x_m); // e_x_m = Pc_inv_m.dot(x_errm) + // // compute w_x, w_y --> weighting matrix + // // Since w_x is diagnal matrix, compute the inverse directly + // for (int state_k = 0; state_k < KC_STATE_DIM; state_k++){ + // GM_state(e_x[state_k], &wx_inv[state_k][state_k]); + // wx_inv[state_k][state_k] = (float)1.0 / wx_inv[state_k][state_k]; + // } + // // rescale covariance matrix P + // mat_mult(&Pc_m, &wx_invm, &Pc_w_invm); // Pc_w_invm = P_chol.dot(linalg.inv(w_x)) + // mat_mult(&Pc_w_invm, &Pc_tran_m, &P_w_m); // P_w_m = Pc_w_invm.dot(Pc_tran_m) = P_chol.dot(linalg.inv(w_x)).dot(P_chol.T) + // // rescale R matrix + // float w_y=0.0; float R_w = 0.0f; + // GM_UWB(e_y, &w_y); // compute the weighted measurement error: w_y + // if (fabsf(w_y - 0.0f) < 0.0001f){ + // R_w = (R_chol * R_chol) / 0.0001f; + // }else{ + // R_w = (R_chol * R_chol) / w_y; + // } + // // ====== INNOVATION COVARIANCE ====== // + // mat_trans(&H, &HTm); + // mat_mult(&P_w_m, &HTm, &PHTm); // PHTm = P_w.dot(H.T). The P is the updated P_w + + // float HPHR = R_w; // HPH' + R. The R is the updated R_w + // for (int i=0; i<KC_STATE_DIM; i++) { // Add the element of HPH' to the above + // HPHR += h[i]*PHTd[i]; // this only works if the update is scalar (as in this function) + // } + // // ====== MEASUREMENT UPDATE ====== + // // Calculate the Kalman gain and perform the state update + // for (int i=0; i<KC_STATE_DIM; i++) { + // Kw[i] = PHTd[i]/HPHR; // rescaled kalman gain = (PH' (HPH' + R )^-1) with the updated P_w and R_w + // //[Note]: The error_check here is the innovation term based on prior state, which doesn't change during iterations. + // x_err[i] = Kw[i] * error_check; // error state for next iteration + // X_state[i] = this->S[i] + x_err[i]; // convert to nominal state + // } + // // update P_iter matrix and R matrix for next iteration + // matrixcopy(KC_STATE_DIM, KC_STATE_DIM, P_iter, P_w); + // R_iter = R_w; + // } + // } + // // After n iterations, we obtain the rescaled (1) P = P_iter, (2) R = R_iter, (3) Kw. + // // Call the kalman update function with weighted P, weighted K, h, and error_check + // kalmanCoreUpdateWithPKE(this, &H, &Kwm, &P_w_m, error_check); + + // } } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_tof.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_tof.c index 9d4b49280..a8e96875e 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_tof.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_tof.c @@ -27,27 +27,28 @@ void kalmanCoreUpdateWithTof(kalmanCoreData_t* this, tofMeasurement_t *tof) { - // Updates the filter with a measured distance in the zb direction using the - float h[KC_STATE_DIM] = {0}; - arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; + //COMMENTED FIRMWARE + // // Updates the filter with a measured distance in the zb direction using the + // float h[KC_STATE_DIM] = {0}; + // arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; - // Only update the filter if the measurement is reliable (\hat{h} -> infty when R[2][2] -> 0) - if (fabs(this->R[2][2]) > 0.1 && this->R[2][2] > 0){ - float angle = fabsf(acosf(this->R[2][2])) - DEG_TO_RAD * (15.0f / 2.0f); - if (angle < 0.0f) { - angle = 0.0f; - } - //float predictedDistance = S[KC_STATE_Z] / cosf(angle); - float predictedDistance = this->S[KC_STATE_Z] / this->R[2][2]; - float measuredDistance = tof->distance; // [m] + // // Only update the filter if the measurement is reliable (\hat{h} -> infty when R[2][2] -> 0) + // if (fabs(this->R[2][2]) > 0.1 && this->R[2][2] > 0){ + // float angle = fabsf(acosf(this->R[2][2])) - DEG_TO_RAD * (15.0f / 2.0f); + // if (angle < 0.0f) { + // angle = 0.0f; + // } + // //float predictedDistance = S[KC_STATE_Z] / cosf(angle); + // float predictedDistance = this->S[KC_STATE_Z] / this->R[2][2]; + // float measuredDistance = tof->distance; // [m] - //Measurement equation - // - // h = z/((R*z_b)\dot z_b) = z/cos(alpha) - h[KC_STATE_Z] = 1 / this->R[2][2]; - //h[KC_STATE_Z] = 1 / cosf(angle); + // //Measurement equation + // // + // // h = z/((R*z_b)\dot z_b) = z/cos(alpha) + // h[KC_STATE_Z] = 1 / this->R[2][2]; + // //h[KC_STATE_Z] = 1 / cosf(angle); - // Scalar update - kalmanCoreScalarUpdate(this, &H, measuredDistance-predictedDistance, tof->stdDev); - } + // // Scalar update + // kalmanCoreScalarUpdate(this, &H, measuredDistance-predictedDistance, tof->stdDev); + // } } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_yaw_error.c b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_yaw_error.c index d9f903805..e0b256490 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_yaw_error.c +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/modules/src/kalman_core/mm_yaw_error.c @@ -27,9 +27,10 @@ void kalmanCoreUpdateWithYawError(kalmanCoreData_t *this, yawErrorMeasurement_t *error) { - float h[KC_STATE_DIM] = {0}; - arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; + //COMMENTED FIRMWARE + // float h[KC_STATE_DIM] = {0}; + // arm_matrix_instance_f32 H = {1, KC_STATE_DIM, h}; - h[KC_STATE_D2] = 1; - kalmanCoreScalarUpdate(this, &H, this->S[KC_STATE_D2] - error->yawError, error->stdDev); + // h[KC_STATE_D2] = 1; + // kalmanCoreScalarUpdate(this, &H, this->S[KC_STATE_D2] - error->yawError, error->stdDev); } diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/Makefile b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/Makefile index d8930a3e0..b9898090f 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/Makefile +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/Makefile @@ -32,6 +32,8 @@ CFLAGS = -mcpu=cortex-a72 \ -I$(INCLUDEPATH23) \ -I$(INCLUDEPATH24) \ -I$(INCLUDEPATH25) \ + -I$(INCLUDEPATH26) \ + -I$(INCLUDEPATH27) \ -D__LINUX__ BUILTIN_OPS = -fno-builtin-memset ASMFLAGS = -mcpu=cortex-a72 @@ -61,6 +63,8 @@ INCLUDEPATH22 ?= ../platform INCLUDEPATH23 ?= ../modules/interface/lighthouse INCLUDEPATH24 ?= ../deck/drivers/interface INCLUDEPATH25 ?= ../modules/interface/kalman_core +INCLUDEPATH26 ?= ../lib/FatFS +INCLUDEPATH27 ?= ../utils/src/tdoa PLATFORM ?= cf2 @@ -148,7 +152,7 @@ OBJS += build/controller.o build/controller_pid.o build/controller_mellinger.o b OBJS += build/student_attitude_controller.o build/student_pid.o OBJS += build/controller_student.o OBJS += build/power_distribution_stock.o -OBJS += build/collision_avoidance.o #health.o +OBJS += build/collision_avoidance.o build/health.o # Kalman estimator OBJS += build/estimator_kalman.o build/kalman_core.o build/kalman_supervisor.o @@ -159,7 +163,7 @@ OBJS += build/mm_tdoa_robust.o build/mm_distance_robust.o OBJS += build/crtp_commander_high_level.o build/planner.o build/pptraj.o build/pptraj_compressed.o # Deck Core -OBJS += build/deck.o deck_info.o build/deck_drivers.o build/deck_test.o build/deck_memory.o +OBJS += build/deck.o build/deck_info.o build/deck_drivers.o build/deck_test.o build/deck_memory.o # Deck API OBJS += build/deck_constants.o @@ -175,12 +179,12 @@ OBJS += build/buzzdeck.o OBJS += build/gtgps.o OBJS += build/cppmdeck.o OBJS += build/usddeck.o -OBJS += build/zranger.o zranger2.o +OBJS += build/zranger.o build/zranger2.o OBJS += build/locodeck.o OBJS += build/clockCorrectionEngine.o OBJS += build/lpsTwrTag.o OBJS += build/lpsTdoa2Tag.o -OBJS += build/lpsTdoa3Tag.o tdoaEngineInstance.o tdoaEngine.o tdoaStats.o tdoaStorage.o +OBJS += build/lpsTdoa3Tag.o build/tdoaEngineInstance.o build/tdoaEngine.o build/tdoaStats.o build/tdoaStorage.o OBJS += build/outlierFilter.o OBJS += build/flowdeck_v1v2.o OBJS += build/oa.o @@ -192,7 +196,7 @@ OBJS += build/activeMarkerDeck.o ifeq ($(UART2_LINK), 1) CFLAGS += -DUART2_LINK_COMM else -OBJS += aideck.o +OBJS += build/aideck.o endif ifeq ($(LPS_TDOA_ENABLE), 1) @@ -283,9 +287,6 @@ build/%.o : ../musl_libc/%.c build/%.o : ../../../Source/%.c $(CROSS)gcc $(CFLAGS) -c -o $@ $< -build/%.o : ../../../Source/portable/GCC/ARM_CA72_64_BIT/%.c - $(CROSS)gcc $(CFLAGS) -c -o $@ $< - build/%.o : ../../../Source/portable/GCC/ARM_CA72_64_BIT/%.S $(CROSS)as $(ASMFLAGS) -c -o $@ $< @@ -340,6 +341,9 @@ build/%.o : ../utils/src/tdoa/%.c build/%.o : ../lib/vl53l1/core/src/%.c $(CROSS)gcc $(CFLAGS) -c -o $@ $< +build/%.o : ../utils/src/%.c + $(CROSS)gcc $(CFLAGS) -c -o $@ $< + diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/activeMarkerDeck.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/activeMarkerDeck.o new file mode 100644 index 0000000000000000000000000000000000000000..d4ace454eaec7eb40fc3a525cacf43c0640a66db GIT binary patch literal 7360 zcmcIpU2I%O6+XMyp#chVaGakukefC^u4xwAO@g;n;;tP#wwe%QFG-{n?OyL*+bgek zH+Qd%qZD;3sMLo(*lHelK-2^(*?sCm5Dh<)D=L8mLQzNy4-upx6_JooswyH@NzFNP z&+(4Od#ixNMBX{`&3C?YX6F8!-8|QKv_Bq;fwUO>4C*660i5lctxN~DK`Y!l_lu=_ z7R=u{9bei8F!y#G=KqzmmUf{1!ANYW1^bJS!2HUiu(A_vbUnY_a#lVCu+>Fw{5!Sb zJ$s#`6RQn>4d9FewTFlU&pIzt@5Y_vn;)$nSVpb|wJV#THat2Jbmy92z6qS<D-fT| z0;J!wV(oE&<a5pNKH%KDAFZZejl;p~ap%(RCOEV7Zya|y$%R8sayM+6v~hgXYJKfd z)C0`thGn(Cxv4h%!ZqloxEGK|`PsO(M{GzEc6D`iJ8{V`j()@^{O^eGwyn46@7}pz zh5OM0E3LTRAE5^A!+|y@c@;1pYis)lBdMi3EzZilbH83(wleQL;lMoV%)M*1yoNp5 z=W8)INZ20A51bV|lS?+*3voy`(lGs(F&1Gd&Hpy#k5~-#_JDJV_WQ;IuRL@CHB%q1 zB45S9m|+eVaqlTli6{BWTJ`nHSyyqr*>)#sH^D*7na+Fe4(<h>+m$^2(HW9{e5cww zwbq~q<}bu*S7Mke#-cqqPkVP0?S;6r@?E?(;_>=^|ILDS(x$l^$RWMlOn63=FYQyd z9g?)qlJhDy)P<PU6t^sZZ%n(zLiKF5BatF_ZQPmYP~%i@dhkSF=2&X@>AvA7?ZHy6 zJXLXn!f4U6^ImS!?mvl_Fo2s23Nzj@*PrzK!-y+q{4o4!3SI1dRpqtbk9<ahkx~`= zLRaoMiByAfC8LWI2^+<xel(ZTA~RnmaemA%mjdFsA;0L2(GdK?_yieK<-AAZO1W61 zeoc=C*!0lHklQ=qmd3q2{Blb;|KEP%dEHktc`|-J!dvFe=_tHr5_ue@-xk6Df8(1Y z;?^SYsQf1)_)$7=q__7;yY0x=ziFq-<zjBaEtKrBvTp|yo}JoX@ylZcyaiHzZlVx) zxnSD&>|~;Ae^*CmGSS&(x4Hh*ezZCsdyMczr%f}R9bNP^`j|%N)dcUWd(@;^4c|xr z7XEA0EL1YvRt0RlD(Hb2*Yr1Q6bm+)GO$Y_8}Z$&)6D)i+4BJ77(}&2#zUQr`48fJ zOk0<%WQ1|KE(Fgo{vhj0`ezvbjDd%7#hWLwdtUMDxahpZxWpCw662r5o|@p7mE8pV zm|MgD#CS82u}NO<p&i5X`n*ExI{#pNuYuFhf=@77@4|I$#CvexV;Y}c?$oH{Aza3i z7tL89tEExcLj8?6&01@#WioalUv{C6A5wAacw2o6b>tN5V5qYZKdp4?c((3>I-k`> zp&9CI#LG&jjxTGT7U;X8>ukhdP&##dV4cqAv{7ijjQl#gKD`uyUqXBfUMDtF<x2fc z1pjvt_&X8!Un1~-M&KVt;Bma(8m((f1imu@-xq;D9)W)q@h#eQyLP4OFLJ6v5;@pA z3xQjmguVH7uX&nHd(~hAI9MtKkel{>uM`aC!S~KgBhAa}HaSzBAiTA4p?bpe3u6VW z9lRM7NMi*u?)mF#8?C^|RNS-0vYUr|c?e4rlIfWaf^uoZD^<%r6sjtl8PBg45Dff6 zX`G9uyum%;7N<SPWc08@q55I3n#)9{kh!l+QMp(iudY);tm69aR1``nLgvWP<2|XP zndANaBYo*iI@NQuF9TSM2Hw<3w-Ag3t{<pEum9V)ceGA8)|G~tG#=VvujrmtlReW_ zT6o@@IqBo8c-R~7UY9qPkbZ8e0=Y77T+thv4)A5}gIB>V3&voU)Ovl-4Lq3grm9}R zYQvtJS7Lb|D_cK9IcEx`v9h}J<cZUQ*T4Sul54)zz<2QdO8hUeO`Xj);c_n%^tgt9 zfo<wK*nSxK!Xb#>uhf!=?+;D&`4rofkFK9)oOBWz{}~PcvW92b-e%}bFmA5*EygJy z$(f+5j8oiBwyC?uwwdR34cGVK7UQJT#Wr=f**4?iOHMU2?k>j7{kIu6^BK_i4{$8% zhBUs8rx~ZXPiXvSG#&kV$TM!9V})^Z|6kN}D6U+8_~lkL%3sINGj8Vd15HQI=O>Jt z`Me&%zZk)Pi*Ymm-)nrihAHvOnm*-k6Nv39<FYPWp#XnooYtk6*w+|0<35P*32NrK zH#2UY`!0=7`N(_S)^IkJ?g33l=Rc+4I^W>|<$p*igdb@Q|B8m6V%&V5WEnTF|B9v~ zwI0dMYC4o>mOyOJYC8J4e2;P2|EyvIyrk*t`!DZbsxwKyna`t*{RmgC>@Uv>!G-T= zeA1EonPFAO$}?6lMdP?~KkNArU-m+LDK0%Hg(tn_Un5a$w)za~XUb=e$NIWRXD{Ot zM|8f=xWm1~mHK~3!%2UE$M>7hb>{2&(0fY!&3tY#-{GF}A-;UCG4r|2yi*2WD*6cx zr~L2oxT4{t|7jlAG+aO57d4#t^4^vGll_$Ms|y;R_FwXUUBf?aKi^=UZSa?Q+@|5A zFYE2raMHibV@OobP6h5L_JJSv6Jq&T!z2Q4Hh@Il4O~c!R;!Tk%QPT*XQCU2L{bP^ zIGHGxb8b;^tVs^5@+46&PeK<}?O|C+MP@=TezhW#Rj_<p$6#1haM2U0hD+ejfm2w` z%4+}T-bPQn<g{<7p_CJLu*lB`9<IITWc)B1bRLcX+;{L-x;Fl)q6Kk^vzh02aQ{Wd z=^E49Esk6NW*E+jzi_D*Bh2)_%l`X>$i3-LwGic{*D^#E|8APpn)nOchjV0`@jGZ! zunmOW+Nbyn;GofH|4z|{Vauvdd|zTuzb=Ts?BBN#YZQN$;|rf<*8F9B3XMkb-{ANX zhlZpjdV<d))+m0B<G10w-o#(9DjJRAU*`A&Or#;*^Wrb@e~eh8_=_Ari}QLDf5Co; zMx*#UwuX#3CQ^KQ28zGL|2blf;&0~bei`TWCjNr`6pcpl7dieAiDRSqbT5d%#Q!5= zjpF~7;}77x-o#(9KcLYl{@vD)k!2#qZ^l3Im-v50jN*6TpWd4Jr?AsHh&C^0U2i;M zlt+dAE4&Wc4yupM`1GDJ?>!Q@&M&y5hPcEh4mJAkghu|S@IMo&-3q(4Pt*TD3Uu+* literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/aideck.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/aideck.o new file mode 100644 index 0000000000000000000000000000000000000000..ff893923351f447170dde49533864db9a1273c0a GIT binary patch literal 3952 zcmbW3PiP!<6vy9Y+WM#dOM_Ug+KC29#f-a43yEH4n@u*s)P!^;1(C^Qcaj~tn_Xrn zVPh*s5HEU2uwW4n!IOINBIuz=5f7e33QCS1ym^WApgF|&-u&K6ewm#?=r8QN_xt?5 z@4esrW`4iSyJJ)1J(&zh%fPpA*b@q{^WdRxN3IR0pchP7pS^83znwLWU+K4Z?fWnH z4A{JT5_VB`1KwGmjqG*%<H!PR^kWQwz1s)&$nQqqi^R!hA`Um~%=#T+N~^{TINpcx z?H<^qajJ)LUy=Xs{{9p3`l6jbfps!)0qmQzCTs<y$9vpBi*t!`Z61g9J5~G{`0II6 z&6)0P{sfHNJ!$XmUHjn+y3fMoP;qSZwV_gB2EzfWUgav;g-T(v$UgPkVYB7PAog8f zbpo&A`K#W-TIi8X>0}W5l!y4OQ*^!e_FhUT-gjbKPow~8d1@*8v^-E69eu?dEWQ4Q zS#CD#m741>n~TlB3~QcQ7-|L0MZb<-P^tN$R|!`F&m6JxL-}lO#LDH(K{sd&p_e^( zj<}UGX(X4;Ur3n<W4hmC@YjBl%1C_E0Sx?0Y6fPCH?=LgSM^~O_GtO<=fKm<ALIUY zwqy)AuJx4LADM1GfSmHvOH6G(x&pk6Hlxi`W~TCV&;LB@MJJZh8E}Hkk*4x=^FL9Q z(e%SwlmT-0hfw9|=A<w{J8U>a>AU%>IG)k;6Ram=z(ZP3xhhXLr%jj9^hfhN(v@cp zi9ADna4Ch;A(5nCP2nG<@K00t=PCT_6#jDx-%jCwAn(<l<H3_tXO~rhfes&XWv?AV z$!!gn-S$-&s4|{h_CtuyJ-;3Kj#F<gwH-eE9H-?5ZlkRZ&GuS5^cr)nA6^dKAcRZ# zGOSX*qE~m<z$r~lUo1>H)8pfp$I4E*aB*tP0XmqS(#+(vGdX=8TK@8-X4QkLzvPE* zeJ;Rr1y(RwuH=P9H+1LxuvYXI-IaP+_8VSvB~-)F<T_MrH1J#uss?ys2Ru<e)St%n zpmrt$@RV|+EA2~a#Lp-<y1v9dafv0AW!{JU8TQG@{ux33tj3G%Q=YRLpV7Ff@hckF z>sB?c>s!oeKF8Q66SDt!jCYvF=kvbC``IV+8T;}4Tg>D6zhO@KpJSiQckEN1gLe_x zEsgh}FMIAbbIPylf7H0H-)2sApJ$(p#L_1d`SS#^4Jre~DbEJ?voX%y14DZKbcyF5 zW~Iqi>e}4b>*~)-;zU2g`gnd>ACt#Le>x>UPB&`t{4x))+G~x_T|gTK%GSgSaPL~7 z*9pO@;{F3`q1^^6Xi|sdIcpfZB#H=nIB3<I6}K)Nzp#qYZnV^~p?0GR!qbE)tD^(O zioUz7O0&`MmgOzxo45yKVhpW8{6C<LjM|Pe2Ul5N0dywNbFu}n9llRF|L_7oid}N$ zdCBv5fqDE3B`Xg`r8&69F`Yw{GcBIpUA@KQb2vyWuZz%^`s%Cpa8TwidB$*v{CNGF zERgp~GDy7iZFG{>FZ+N}Ot6sFkDigl%lf^AEUEr4TwnB@<{)1BSI|kS-{JaFhw4)< z$tV16WJ&e6x&8!>>rLW?t)P=se}n7Kvykf3*OJ6b{ST2P)i?RU|6lzNFg~gNPC|Y9 z%8J+jgzIO~>aE80-_#-cyevm-{2ir`pBQ%d#iD&j|Ci(SX`1nO4-weBq5r0i)}+3m SUUZV;XZX`}ON4CW@&5t0+d%#R literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/bigquad.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/bigquad.o new file mode 100644 index 0000000000000000000000000000000000000000..8f67334bf3aa7fba349274d76188b3890045ab0f GIT binary patch literal 880 zcmbVKu};G<5WO@N6fv<Ov6zWgB9;@0p|Av1&;>EU#N?zYiPSX3aV41e1wMhl=y&l2 za87MCa?AiH+3)V%J)bYm`_0{L&-1{T2OHQ$h6Px)$he_n7{ETjbTYXl!|DAad8n#I zn)6~w=9M5a&&YMK64ks|peNG2kXb6%A|qoO1rZC!G>piQi!wlujYf*6AyJu-MHjo? zE>B&j4`1J|obQ|fz=xiz9C`m2zTf4O;`wFGXEX(%^;;=<f+)onbK}YERRW!H$$=(y z4K%IFGF!^-d4FV1uwKo+XX#=qHeu`88tN2x#n}_bO}4w)`ZFvU;QFur9JT69hO2F{ z4xZX1`lf#yU9b45bsrkl_fbpTRoU?t-~iFSyGk+L;852YFnvvYgpNypr3>xf*4F<3 D{@piv literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/buzzdeck.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/buzzdeck.o new file mode 100644 index 0000000000000000000000000000000000000000..a8cf2a882eef3882df87e5f0fc2683bd2a7173b9 GIT binary patch literal 3144 zcmbtWO=uHQ5T0b~|G!nyR&bFbRqT?)A6ij}wzgG7#UBtA(rvOK!6aK>wo<ENy?XEm z^yEqKpf_(`M2aVmUi93fN2M2gC_1xmrg`1$dU0TPX1@2$%)WVV-|oZH=Z4d%6o{nY z1GGFr0luti+4<1S!&caW*32cmZQEm8-{@Mr_vziD1<&W#!NR-+2j(`-Y{l^xb5`ep z`E~h)#e1LMCh<D~o{gpR19JdJC<d=*cs(cE#yVqZ7?2#ZR^dD1Q1XhmNRJm!O-@gH zifoc*;7=4}P(#b^A3K)0u$f$IIrcB_QNmy)0iQ|0VPtUdnB6;a{;GY&_iM$9TW#27 zU)e#$vrqO-D8F2-p{0tIYTy-vN#)rCPOdMP$qqQ#oZaiHdLLSu{rd@bvNnxmGdb$u zKZMq}1AhI9qgb&!fZ7w^APX}^Wqk;=@1#wLr;YrpIk21Ya2?R@WqcpwdG?R9CS}12 z!_(%WP_^Sn5l<P<DNm;P?axnXELa(4GjE#Tj-NnM%HYd9DAod*Wh;};(~iFk^R)2( zRtV-<Yk1n!dD?LrwLq_e8Kn8`_*o>S4F0GQWWh$m)8;i)<{X7kPQaT9_=5!e3F2Ff z`7U*29A9&Kubm?FOaXaA=v^q6TXti~JkzKK&{KkHGqi*~7^oT)3KOn!>rH)1OjNyT z|FRcca)YW5;tebBwsw}{J%y}6zY!?E1|?O!<EaAWMP(j0vZK0iqwT`Ei1e`09l;MX zPW&z*qdv!WC*qQmpo@&}h~Ts?B$S`tDUq9OP@W9}q8?*=dju~rPI-2-O{&Irw60L- zQ<4@3wXB=qvS&<ujlt{XSmEc{7e%<_AS{|kcs3ivPs(rhQ{FS-@03JN^KLzG$H8d^ zO6!VP%B#6f;7tYKl-$4tXS~@2NBQIsJ?r$NOQaA%%c=QAw-yDJzZ}Q?JQQv$$J|&t zQ@CfHaHly%zh3tmfjsGdX&a-lRmKUX)8(~-`>aKoYd{$7HR@*`FH^4ZQT&rZI{> ztef<i&UwP4Uzm@G#R+juIfxGBOp1^4qka}+3CrPS$}Bs3O%QE)e#vthF|woee{fv1 zUlPy5Vc+8VH_D%y3=^q;1WCN~?>b^}^?!3*KWkAEFaA|D;_6Su)Tda9m-_VM6<0sQ z4HCZ8i~9A1`fs_u)S>y)*G}REe~MUK{eG@LisPn8ykL*fh@1Z`*B@gd)u*qg#7q5G zh*2q7Cp1Hu;rcfOV9jtCLlF7qxydw`W8zmHq<uu+lW2W9<Dz?ya=fQWp}f{==`QsJ Spg;Mzc$@$G-w2U)H2yDShU!WH literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/cfassert.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/cfassert.o new file mode 100644 index 0000000000000000000000000000000000000000..828bdec417db66f62ba1f0a589972e198f3db4bd GIT binary patch literal 3776 zcmbVOO>7fa5T5lWX&^!6w?&1jFD*ea3adD@5=50)+vEo+N}||Rsh~0&dtFD^UbDLv zKdFS<a^RRqJ#YY(3sS?0o{FWajVcbU)Ju`5dV|m&$_+>_mPpf?-FdKV?5gcZ&ol3P z^S=4nw{Lx6czh(HC?G|Fui^PjqNux{+q!4!&;=VI0x<uZTDy~ceEmrR^u}AT^dt$e z7~c%_B{lQQ>fE=Bt12w4q?E-KRk`t}8rgR*q2B%CuzL3%j%A$RSGV0j%Fi+GJZj|I zzVCsD>5U$M1zMxg1GQ-#hqP;K)13H}Ygg|m@XZs^t=B)rwZwPVZ0Ov%6(F)tbVHqd z-VpxyYi;dSvO6)}L(Kmu=HIF4jiZ?V1_c_>u0$i7BGI-TYP93^wkXv?{*>bb^iQCF z57s+_{%>NvavgJ-Ush|=@yFNgPF#;DdOZWmsZSJ0EA4vya3`Dw71D>h;k1aLZbMCL zxX-UuZy?9^W^+J3@=>?w^+@}3KZ#3h?KAjU?q8i#7FUz75ZM&RS`t`GGP<GXNR;+G zRH6Py7u2bLt8?*1+_xa>kbR=(M_lv_vF>TC+ZNc{l`d!;K#puguU~-3sTx3frAu$D z&VBzSam;k!Ggw=DTcD53h2r?5HhrN3>Oue12dN<ucO27pMc$Y#nmN(y4E5$V;s%l? z>xLU}@z%!-JC`@AMOPE{z>w%Y)-UWB>p|8BB+fw5_JK;4wc`P;<D#3hu}MDtVy5bf zYWY;zI#U+zxr#{~US1QHF#OVH%X!N#8SboA7I~{$ezCrE!4%Fp$2CjBHl1n-n_%Q! z(-wy83DX>ZKR!KibYk>FnWopHfAuq(Ob&^@(TVp&+Omq-f-y^(*uurw@%<Is%473I z+|CweT{G)eZBrc52KNsR#13h(LD6T}rTu6PM5BajF+nS_fx&nFIXa#JXoJUV&Aim+ zHx9lgYBP64+t%U!^+ZwDiwf=Qz?VH_Jx;I+9WDIV<G%k(>-_Q3fvthM1bgg7y_xNx zdKV{K0&)9zaTqo62%cYIJ%zd%Po@R_Q48E@fuC=IUqqbpSwc<H?<=^9n(#+F-_80f z#y9h$xy|^GjNfOxz&K>{{u$S@u;(o7$${fqw&~vtBX~5A7_I@C(ecSdd^|HbGLjlj zXVUS+_;3cCvQcpgmJ2?^2wo$QwaSiFG^eUA9(5bcialF)^MLnDvS=E1yjUbVWx7zY z&X{(}wJO1g&u$biY#^1idDitXkI+vq#qm8noA<#9df$sF*Rb8R>A12?skdSMfluo* z`w-%rq!a2fws#@k6~M>YCZ6Ewr1L=%=0D-XK>YqY-~%Ta-x1=;F-~!V=S@B@!nd#w zDOn)l^bSa=u@T1UJdqH-%{RT@CAP!)|HOE>Kl0p#{hzk*m*+9;zZ>%)3G<IJPX5&A zo1PcIIODQ!5}yk21p7=MdXm>r2m5)9amoLy?*=Crm;4ex$$0oV<`@t27ef4k`HL-h zDvZmx(*NTY{IwAOW#+%wg8x#8U;59t;J+N=*O~uHh)3eL7!UX7Hsf^Og8l!U@$h+g z8sG`Oj{^Vrl7#v9FfN}XUWuOcF)sTl@qWg``3wZ`S9}WpS98vlTw?|_$F+T3kd|#0 z4b8=i3A7yDlG=>pfM#1XA@`Ve5VZ379D-S^R5Hu*WexKGM_Zsjl^DExh(f0ylrgTu zpS{>~!gk?k!=d8{%31!T9;8K-P8<}6G|5h1!CusahyN*D3dLo2*>*YgzF)-ofA`05 zFU22x#^@U|KAn%C$owU&<6^V?f8d1rf}7En`z1WW`v)Yz`VsFx9>QhZpl;TxDek+@ riyM%KzB@9$>_6e*-ciVTJ`l?^35bj<A^LVS+kcZka+A`Lb$I{Z1_RF$ literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/clockCorrectionEngine.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/clockCorrectionEngine.o new file mode 100644 index 0000000000000000000000000000000000000000..c4bd6c852f222eb26f950a9e2ed933ddaae6bd2c GIT binary patch literal 1848 zcmbtVO=uHQ5T4COjUv)k50y&tC`D4VOA-)T56!l*=F*Bvih>85Znq|wWaDNF6-0X! zPaeGJK|Cmkcoka^>BUp^Xz?muM8uz)7mYLNOuN1=9(2O)%zX3Bym_<xHa8|FPsR)b zL=1QiTb`f*%keGS?wB_0f!%1?KUd9*>nUZvrE46_HR!sY9EbR)Re%zJv1WsFA0U3q zK&^Ubl41UP6P{p^+x=L_#7iaY6=QfdnNd!1Dh8z(#tMj&|H|0#Q+weGVH6uf4GAY{ z!&s_9>&2m4C16Ft(pd%2>Ft35$7l_MxQKVDa&oHO#@_zK9{p;UBqtV!GsNx3TGa26 z>chb!eKRjvkG^?L@;QI+F3C!M<jb9X>+P@k4>zCvH~`=BP%IRVt90?yv?_UC&8d{D z4K?riDyX<>Y^dpb^VJ$!zEi0Nt`jWyt{Sm&L%B?L#LDJWy6o47(8>%B5^iM`MY5S3 z?c^^)&n^z%+ffuV^2q|2_=^$~E9r8u14O+cRA+}yheI7?J5I0(JGb#ui1dW|OfX}Z z@h<k$tj{rSv;UYiI5p3?T=0A!hg<a;6OBvNhHE)6um}Tl(b1wCL<b7xnzK+V2X1tD zx;aO&j-252_v47dyPIS@so^skU-mnv@da;ce3{3h#uxmW#_wf+N#hGH^OOD+^PXya z!Cx>g{51QktYyD~gVnlP56ZKs1AjwT#PZ!**$Ujn04yA68LZh>3oPFw$8uW1Fj$UP zue*(ai~omGm`iVQ_!&_-n{Fr{H`L}`<|#lQ8gx2r0a%~rqonwV>_VK(1jl90hZ)yT zUYhfmzNvKhC`PE}zvgE#mumLl6&6`P69&<i{zZ=>M)^ALJU4nl%a{Jc8o%G$WSI#v oKU$CeWn^8MA7T35sn|O%+9D?;vaUegXhh{V`IA=^B5OVWH%#Tq3jhEB literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/cppmdeck.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/cppmdeck.o new file mode 100644 index 0000000000000000000000000000000000000000..a9c70c39d24dc7ee8ffc2c23405723368d4f8d59 GIT binary patch literal 2544 zcmbtV&1(};5T9gK)cVm<6tRNuP$UKWNFqYxX-llF_(2I31eIjF*^*$=4ZEvEdN6_q zFG2<XfFAYc&6|k-gW}PnN2RA8iq7o5Ngi)Ey>vo$W`6HCGcPl5UtTWVy_L`9fF%c? zVdOCi@aO2rwqw(VNjOW^Hh^9EYSn*S7S{LutuG(<EqJ#(0ejQ9*2vqH0l;<Sy%#X3 zHS$o|ov`=zx4wO#n5O4G#Wh%WtE;Q`0K&-c)fuD(Lj?Jg26%w`YRuZo7<@1WhvjPZ zhA1rGe<0R;zvH%?_NLhI0}-`6u{hrg{Ec=8t-x)yBhQVV1)iwL@_e~is>o7V6r7+t zk5+MRj&NBLv{EXTsWS%%&Eg3B{g*|tGA9LK;U`Nh%w)=`7)Vc?CY#stCp>^l3g;0N zwS*REheY9Xu}<Sx5zlG+;T<IW^gbz#1;^rS`Xk||@fwnH8h=3xvf#MpC1#Q*jnk?H zC&%#9_%&qaG`@b$EZ{DV(k-INy&RzcchH&A_Bq^{+v|1d{g5uq_JO@MFN}uH?ag)s zvrTA+u~o14oWSXZ$!q2Hqgp@4n?d`z7t|?5`i+~$f#_3U`@DhEc_1<QB1QpBenH_g znCG0bN%1){`TV=-iXxkR&O>+}aqc1KVVrX7LbyH!&d2$gE0n=F^Ypsh6Qc6@Vm|K& zWcZ>RIqRsSAki(h0<Yu92nPbP=|m35^)Lh(_~a11Bp1*nQjDO5i?ZXpPKR+k2sh&~ z%F!5;ka*@YzDcF)ce~zZq<+$&l)z|gq4s7a>Fh)SYvm5-!u|{z)Hj;}r6*N0x0Qby zHPzw1Ur_iJg_}3rK&_jKa_B<$4&@vdZ}LsQgt3H`@vF-~ITv*hZQeiUSwf6#v;GcZ zBz%q%ZxqkIjYd}gc2xgX6p{Kzw<6c){yjk~tNu?F$9&}u<Jo_RMppgbsy^4D`jm_F zG2TZktNt&<Nmddyd~!SkAsSir`LCy;h*Y0$XO8FkuMwmAd{3YmOMyU?M~NCf6&%M9 yNIu;+ro2(af?7O-1iIhM`X>-GXHU64Dey5lns9xFrqIZWZ>Yc6w@g&pjQ<bn2Br!C literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/cpuid.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/cpuid.o new file mode 100644 index 0000000000000000000000000000000000000000..6190496b593e74752ca7b3f693a55eb4f9eeefda GIT binary patch literal 1016 zcmbu8F-yZh6vtm1(FzXgqTt{Of-Tr12{`CfDYg{EMV%aMnxrJqG$p-4>*CjNa`8jB z)~_Haj(!E59F+QAnzP}|qz^9d|9<yg-raF`eRN#Q=W-w|2lp_GBn9|L!AguPP=E!1 zuiMAh$=&-{yL{ec+7o<EV}S997}TrP16Hh`oU^kq?AV^=cUe1(nDAV7Snfq(+wY)? zY|j_2Ee4Ux_PJR$bz`3!CM#M|P)4PfO2oOrXvWaZz1iBb6fJiS-X>XdTILP`G{|SA zBiDZM#h9cHC6%FJXVsPvtfu->OtyxD_;MV<j|aOq@EvZ$_HZieu4p(U8xG1^$Lf2h z{*?>B`=dZuE%YLqdQU3h4h3+>5*F}QzYp9FgTU>Iq}PAk1{Txq=arvSl9(x6?oZ+^ z6jZOCY*QvEUOnj@oG;+`YyB?P(m!<^X=^6IMH-@({nI|{wv3aym&DWg;46vON@$%v fXmo$nwG+Qd8k8tVnd~dk3W}`yha^#b9%}tJF(g*n literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/crc32.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/crc32.o new file mode 100644 index 0000000000000000000000000000000000000000..e0a3b990b4d1624c183e510ab5f4d510fb28b7cf GIT binary patch literal 2928 zcmeHI%}*0S6o1>PT8tmahap13qC`Fdo3>(NO-#0}N+86KQcfPsc3Etb?MIevQpLoQ zaPvY9cY}!u@DBiqCWa8tT=XiaH!c|Dzya&L?o3$+@ZwQk(|zyvoA-V*^LBRk#hszM z9!Uaj5-h?#;w-?HZ$DNmp$ey=22KD>&w?771n85XSVwD@Kaj_tPg4FPK*={c9rG=| zw^p{!m%g_aV;jWVO{8M11HjU~@UZQ<G~5Bc!HwF<OL_}f;c_|t1w5PK)z+mcIzIWU z9B+eSY!)Eo)^C-`C;Ssomscd{i_qM5FO+aSZ|S^K;CYGTmmAa@3GfWQ25B?WqP}`l zNGwI==pfER*jl+3dZ2piMDE5tAl{pJH@`=qv^^}%Z-0Z*PXY_;q<&$i9(H$#v_M-i z^OZC%Y><Wuj~K_%Zx4s(ck0#My@}O1)T^}Z_;TEV;|~149q5lnZ_1th_eSJ+Hf!oh zEtQeSvX*Qo4LRJKv$A6;lSY=FOxcER=Pg4HDZ$>LKM+y^LAg`2(!DhDcXc7J1Y{fu z_=DH~-co$0d*Mg<uq<-u8y|qs-(g0ml4vy*0%!Tt&QK`1@_B|_Njs>6G{LWmU~&Z? z<gZX(a_74w3DB>QU_BJqx%OLN<F^=JWcW7o1B_o|825t~qkq&{M?h`JaR9odUkfTa zv==apYYEdB$fWF)W~QDQqtHHDrJdAhHe(wF8*?0DBsZ$rh7;e<Gcu}~dfudbBtJH0 zSbQ>odfHIemaFkafp20ZnD6?OLkr^@1wP4mQD^!HotYzac&nSKKJOi-)>4dy{8=Zg zT$^0{ITsJg_|vqlC8)P8$0vDY8K$OS6G5S^(?Cg#kAtG?X~$>NX(MC1wf-TNX)P{M zJXtE`(0bVV9YpuZ1Lm8l$NQx+%-zx{C)#2JLX_h7ir>Ghj2E9wQ<#^@@b+^Ec>YoI zsCrRG!~t51oLHaZiSEP5=Ay1@AsS(-zsfj4jy>9s1fI*fy+_DFxW?*>ED`sJ=S}P% izNf^sQwkoi{y#zBGCnV-F3{kx`Z+dHgeNjD*8c|9;mwl( literal 0 HcmV?d00001 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 new file mode 100644 index 0000000000000000000000000000000000000000..47a7737d61d83d401a4be63be346a2174f7f9030 GIT binary patch literal 13512 zcmds7eQ;FQbw8^WLSTXk$e0+iJY?B?j3o;hCsN{8PZFOt#1zT36Q{FUt)9?=#ERVo zi{O;yE8{Vq4ziubO+B#;WCGNkGKo7z6K%WLZtITI8HOgQXX?qUWKye{{E_$*C6?9S zdGB29;h|^8<9{-}%-j3!@16TQANSmk_r!s9o7b0wLS#yaUZ7&jphV@Xi}$vBYt!{K zmuLy4@<eUub9@=u4NEDsqcHQCoATl4&n?Ps<9ewT{+YQZ_UFz_glXXI*3g-^!*rI= z2Xs#^1<wWWEI^+^c)_Z-Tbs^I?0@Mr_kVW*jaPvG+a)v*qU_^?W%fAt;VX3f;-#4s z|6a$fcEg2R#@@1M`}f{l)E;@$?ueWyp*x*z_VCI1cJ4{^?VN89XHU>T*9p{RE!BrA z?HqH!j#XjGUdn>E1T}PAV%*sA?gD$<*z$dFowTjUuO}yOWS{>3`SasXFh2hhI6h;` z!@a+{y|h=4Q#p^*DsP;2cG$zqF;?ZD+a4)z>WDNGt@%5|Hj8nJEwmeUV64cpb4|eS zUTH-VKSUcjU^iG19?KBfxfRQ-$jaAOMp#GLqLq=u=s&Z`ia5A<oOz7b;{KD2^Vsqh z*uA!QV!!9x#Qr~ycqCLjX4S8Z>_9vofd5;<)MiOcyg00yHV##vG7cR3*@*csCGU&# z`Jdc;Vck534`L1z=J3S+7v0==`#Kt5fWB#W%(9QS%iL|p_;4SdcRc49H}j7BzkMCg zIgi8W^5)woACGp-cV0K%eX!)r4Y1{T*z(uV-%)8_8Cy&fS?Dg@L%GqLX=+_5!MZYn z_31^dDTVODvn!Ch>)d>G+<Z0uh7kW)ncXl0@nyOAs6E_S*)-fpw0i{WU}5IQ>d||O z>&!nwxAB?%9h7)Xtu+repBY<hPni76BBu|Y2oD(kL#vvGj#k=3N9Nk&hab1cS>KVp zG|oD2DW@T;mU4%iufKBWLmKLUU4<4qH*#!abrklD!XCDp*SlX#tzYM_n(q~ey<U^; z5^8IoYd0{yw2F4W5~4PaW9Z>;K4ImpSKnVu;|mef|AJqmFP088b+^~wM|7;Qly(=8 z3-7|8_ZK6+;R;#PUvcvSem77Vtyv1Wkq;+1hB=y76R8Mgw^^1IX#&<h8!{hG-pONE zK%Cy`C>t1CN)zk@U!@qMH!w!eR@&!Z#yFM0j&6)oGr9WCW-(q(6gpP^x%R0s8~bi3 z*ACtJS#;+!b7|<A*);xh*nR=rdE^B1z9aiV9y;}YV0;-{YES$G@iTTAd&01Xpr7q{ z3HGoZBcn40VzA>BY{Yov25+((4pGUm$~nljMX^X_DdnuK)Iiv;3g7T-L+r*I=V2^M zXbs1p5T-SSaOmvV%^}ymJnVhr#!b~!-clXH8hN?Z&NbKH5~2E=Bg^WmB9sl~N{)nb zp+`cw4)k~ZgB|Rj&V!Hh^9lH<^^T%V$aA&><B7c+d*tkv>JjXtY>(fL?4zOTg9|Bl zT5`>sze8sTV?1>RXbBBu=F)(fn>;_>YYh#&9}k~-0r@m`vy3-ln@3E`5lfspDjLga zcl#V_JA?VxIEQxAENWw$u6#K8ozN1Re+c=CIdyjA{!qhcOUONAjG)cB+3t~hni?7_ zXm`F0921jmjTZR8v1tbQkmnY-8&}Zo7;5JIOX2+$e7P`_)^L6wybjOqZF0GJ?TfkR zpzO90$Z&2T$EVg4UQ14N(7=pRx_%Jjz-N->$d#r?>}uph?(*N>UH#^wZui{6_FX{^ zg2P=O%zD9iXerJAcknkZ!u-NqY+ORSn`U}8!VlN?3wX{p&zkhwIc~$wZ;KB@Xpf>D zLM)>2_4Ip_Z7-MDLpJ6#<ttwuEumx3z3rts`~2k{*7=rNI{%z-43<#C8R5Sm`o1sE z*glR!;r&UR2S1(vdC~E@=y(imw)augoJZ!G*zfH>dY@^p+|-Z_)19#AI4*b2nEj>< zSjfY1UZsJ5#pN{58dwW|-8k2|`Qi0x{<2#y!!vr=e&WD<8agnS#@owi{6Hn{A4k0^ zG!(0x)ey8_P1!K$+EHQb<@oR!*zAp%i)XPex%o1<{+Vt0fghx@bM2fN`w%UUpwFel zb$0Ghvz<G-&>lY$!TMiGIVxWk=~xxYIj(K?cqi;?pHDgO4E^G1*icc7S8=`PGxZ_N zH$I2+{Cf{;4BK@dY_&`6abDZsmo*0*?pb>jvV6`igl{-&BY(%jH=bRFImv4ouVE}# z0LC@v0?$i6w-@~=?s+^9j2!2(@jDN{*<a*e?nU@|0lwzp>q+tT1blrKz7E3ALHMcl z6-sgbc>U<M!Of>rzr21+HSGN%#_!UBM`?(_X;J<XpC3nOex<sjZ04EE`|VtNGmXEA zHPqQbxp=u1X~y+GQ9HK`bru)awV@->Ga9vrw%<*;k>!Z{>~M9VW!)8y^BZ^A;|F0+ z4E7yCUZ5UtUq$0xUjttqjb~x!A>;{<huK3W_Ivvv$B|?3g5-6$)NUw6o^zaO4h=Mw zQ^VmoOYUeXr3QW%;{1U>?)q71p@B)9uL=u7!;^7p7}<{NWN7#YA54D7oSjU*xw0+P zz_O#QkQdpfl`Q9ok!Kw)_x<PtJ+6*BXy3?A==f1+_&s00Vt#$ReLqrt|4@AqtOLd; zqf6Tx<lj?D7t0g;YMm&qA?E#U<QRNJObT%tuu2=Nu|HRHOfR1-8IHTUy?0T(@6P9Q z&_?7duOqyMEX$V;lwj?&aUQa8{#lB%mU#zeefk~P_*+PNy3DwZBCds{lzZCeC+k}# zI^(GM{8b9QN1*oz^xg{o8B4zTpMzw*dKBlbZ*^Pstn*pq%L$9lpIqeS4extw2hpLc z>_P5LtqmNXH^L$8JE7|uOYPkWIm>guk#Nb`(QtUx#QuNAmP^NZ|BmB)({5YGIDakZ zoY;TCJ=^K=VcWG1oYz(n_?P<lnYREP%scAZ;C@dSUuNIz@*}3dWquP^qr=b7Jj}s1 z@wWkU9>e?P0IyrjVPk#styx$KsgbXiEo(P!#!YumOR~2&wyV=gp+&SelkDo^x(68Q zbSBvs^$W4!A6enxe^fab@bK18h-U-jX+ulPm#h^VzH*<{mQ41<yJLx6R#!4*Wx5@! zsk$$f>`L_DE*0-iWSn?rPs*_xYU--%YF9VZtgf?G#8SQ0xT{^clJT0=7C%{CTgSWm zM-<FWDy82}PA3wc_6rwL82_d#VKDj2=UsrcTwN?QOTb?%@K2;(DY#K>@Y@ByC{**L zUMF|~FB4oU1b+bc%x_HMT;#G6a*X$hshdUqg5dcXo?N%^aX;72at~iCIJd$i!rmkI z_kjC*Eq(|%^W?AhgiWNL5Zs#Q;i8642%h!f9{;uRKL`1c8W+R=Z-Se)sXZRk@^tg> zFI@Q|F5#j772Mco>bC?JGflYZJ;4{D<}$~t=y#|?kXj+_ywoL7#Q2!B*GN5Ea7zp^ zJaYxF6@0zO{|&~6dHMyn1ph0+pAwwo#pPDv*@)*{<S|tXzE$w7DE_M87x8k%<+xY5 zzhNp<E$`Ng^R;-l%TvU!=9wA5b1nXa%TvTH)iaDkrN4OgT#J9#<tgIrs$-b0Q!VfI zA0R(}Dq2KUA~6Kq<bv+>9|8D(2jF7?`0oPnQjF7ddS?gV6#;lv0DgM_-WY)22mG`2 z)})yy#<)a){NVunQ~*94fa4>fQKiFABLVpD1MtsaiJ2~*%L4Fv;G7TH*`8Yd@WiDx zKt2(Grvvb#0r<1PS+6B2YHYqBc&*_5o;if?3$FY*!JkGxaS3C|Gkrb8`@JCmUjdx; zZvBiWXGy0o3f?Dpt>E_wJ}CHYg6|dlqTpuT8x(w=tTTq^$Aa5}8~IVevw|Cb-lEvf zbAp?ETr7Cr$NvSve<L^!$!=*EyjJ!v!~ZS8+Xde$@_#S*Il+zIp9y|Z@U<fUd*IW> zzXVGp+g~dWH;Vjn!H)}W?A!)?Iv$FrGJVmwIjcsy6WhC^J<eXIrzTES{gjFAbZ~O5 zBR;p*nP&8%M5a3mp=3Of+2=m<L43ZgNu*P;np#)I)M<Dl6l`Yxwpe;6RdrG~h<ltZ zPVWXM)0+5(Qv~i$;Ye3(ZgXOt)ai7^_Vi@hJhT4XSRn9ba3ywapMtlil6(51y{rkQ z?rclNcF?}qL)4c{Qy)Cqh10pSx2C@C&N_lglz{*ak;&A)Xs45orxJacL~>V}66sC5 z5*bRSTlb}-9I@%$Y0bpqJDc}(b%ECCljg^D<!Fd#uhYBM>7r<~FP4h+rmuQSU_&;r zQ`G-wdz?K^tJ53n>rSQ|4hZc@JMp$euanNidiz`lqcVOXzQKXViFm7ncM$eJ%A-nM zv5s_?*XCjK?h@%JH~Jir+@6ePlHMctHrka+_EL1i=6jo)Hb?JWzrJ-{TePjIdGoqx zF^mZ(9fdoHC-o(qxbsjV?QpX7rJQuy>5TRyF{G{`FgcackBUQ~x;lGfJ<$}hCxza+ zW1zI^tn@OEo0dGR9C|mHF2b?dieYpz%{+uIwhg8y_Bwv}+9YtZ#B+F?vptc{IH`?p zdZ#3)oJIYtuqEZhG7b_ZlZaFQ)G&JRmOUA#U!F~$ZJW}qGC0#eZ*zKjn7|2`d_32j zOkXmwE8|%f-;+u?yE4)3Nkj%?&jF3P;YO$uos@v(El7MX1_7)xD?j?_S26zrjP@q= z{a9P3X7KcqJkJA2_|YH85NrttH-LXbvMm|#Xj8gvYW=_rPV7RCPH#VkCY31)2S|Aw zA1hWAz#{6dpwlaLm(!v!Ay4Cd`vP?HVyk4QXVea_M~0-k&8$QQ!G8~McP6vXEx@?~ zTk=$q*9ThY!_EG;7<kQ;G`_3Iy`QH?@Ed$Q=6u6Ew=159<(~0cg`W=K$t(HQO8zy4 z*D2h*Z~N`9hdwTT`|lFmZ$G{hy2Wq5c|Z5tZ{F|xJjWH!9Ui6ods^Yz{>uv2@h``@ zn2X>3IfDE3T7vuS=l2ONe*4XPrJtuq>BUiXs$>H6_6z=b_@U*GD81&4$YiG#uE#g8 za2=m_6t3g5NR;{GvqW&eU$uh!<FiKLIzQV3cpeGBA5%Qq-*XDr`S6OuwZCJ6vtN8` z=J2ltH*q$2x!kZ{IzCl``{Tp!4P5;3S)+LL{Jl%z`cvLkg=_ndC|uifPH?|H&kOFi z=c3}#_WV@gdc3YE{0p9o?(Yhm>$z}zzUbY$zqNw<^{!R&+OKm8H)nk&dQIWl-%|Os z;`g^)aKGM+;QsvVSGe}~F~!e+*f!-!!5iT3mkfydImPp3g}*Gg-=2#~{w^gyrf?mf zQuzerx4&HB+Wrc`IX>F{C4&3y?^8T~qU^~C?zjI`0DfNa{Hfx(sBrDqn8F*C{09oR z6~0+EVE?#p72I!Ur{Em7CdG4F;mrzvUg0eYFO^Sc%%k(rQn;Q+RSMVR(xz~|KKCeG z$7hawZ@EUV!mrY+@T>GHT(6Ul3GR<4{*#+q{PBER$uC#&8C3EbKP5QZzfQ?Nr||U( zKd1Ps6#l%z=PLZX!g(vJmGK)EobA{0d4+5KpDJAQye2r?zd`9OD14*B&37t)Jgek; zls}%g34Rm!^}1>c?&nz>z_V3wwo~WBDaEhzYB+#DAHaV(fPYNkI^X8Wftc;ttm3ms z;ae15CAdF6^-5mbZ!28K?Gc4*{^tYu*UEP}wo~uFA4t;p<B$LB?H0eC8NvPX{Q>gk z??gQAUsG{-NAc)&`vbxK>vripuQS{Kb;VO9IP*WK@CO8EJ2n5;1^4rJ2JjzI{C}bN zpHlL*3O^;dKR%}g_s8>P!P)+(;*sf1{9pBXo|-s{_!OQMV3G7S@|NJ5hlkp<EhW#m z>AynZa#VB?b5>z~mbXOCmYQ*W&fKbSmN&dqlit^xiFKgPq`bP@+@+kJSPj0UWT>Vy zmWfeKM><V4sU$a8e05Dd)x_hy9?Zh-6Lf=64Zi;1Q%H?V;(m#%(SNS5!Plf-d@vES zK6Pb*0WM$jmogg|msiX{dChCS<t_%!M@?Ivn`%X+cbAp<%F~(km~k`XbgSTcjJRj{ zXZg1%@3o5Of78BAWc>Z-Nq_Sl+{hdKrp<dg+ojhkerEdXImfu^&waSqxcJ_$f2-&} zj%T`<{s!YUZ@T^k>2Dc9sr~&o0-rAar*HQ<@N+I4e?Fp_{wDqou<7*UBfnePy=v;$ z^fv%MpHBa8M8EN$_4AR*^f&tZfwBHtT)MQ2e!Uj*bC%_zYhG9UB`^KWpIkW&YjFAX lvrYc7W3D_WHcDL1_g<^0*R*+<rt6;-hYlJ+sg2zR{y!rJl_UTF literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/debug.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/debug.o new file mode 100644 index 0000000000000000000000000000000000000000..5dc45cbd159bcb86d0bd06f8aaf9d138948f8e89 GIT binary patch literal 944 zcmb_a!AiqG5S=t)D|k>3B6wLrum!Uu0T1<5sagc_q$dxWq^SusiKN?7PyULZ;LU5l z!vF9Kbf(>Hmo+yXSZ3ba_jY!ceZ9E8tXUSQu;2q$NU;F#8rhlC9cVxuX7<A;^t#<s z*6iKfvD=~;MoEz7Y*3U;Br!X4p37p84zVhuBo%Qa#%0Xf+;@D}Yje+M&7jO2tlU<M zc<wRU@m&98)!(e>I&1LtZSsWe$_a?CRmqXJfAJf0MjKjF*x1>OO(b@-zDq?v4#!VC zg2O4y%d0#U0DSb4i6F!*%0*68CE}?7-Va0oJRFUHM@5#!Ihy_>_VEy!YTY=jBk}Uy z5^ov01H|MvU+mn_DQLdn5pFd8;6Fw$o$2DzL-oJcNvu_WJy-pLH|d+nOz%_2MR%px gTO^==Va`rlkFvq8)TyNUD!h$Fm470I=9f49Kg=jT1^@s6 literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck.o new file mode 100644 index 0000000000000000000000000000000000000000..3a0f830b982e6c8a4ec5620b68126a4d2c61f378 GIT binary patch literal 2800 zcmb_eO>7%Q6n@@K3oU;sb`ndi)QOa!B*LrM0?||;)_)16rm31m0!7Gm?G3hKd&7Ez zT6$<DE*v;CQt!YGTfHE)q6ehXss|1nY1E^W9_axTBJjbO_hx6(&Bn_C@uJCl^UeGD z-u!HGHJhJTLLrb6g74w!Orij5&px$vZt8FpjzI6q53QaG8@tO&>(7$f8UwhF%Qw6O z^IhLnVP+f0IKW0n(Yv&MSAkDrLtsR4J&HMYmO`yjv^N#lh`_b;M*$+zx0uqq9W~q@ zkLX<nZ*Sf>49D&&kyTK@=%|qy%BSdh_c7W#DzvxM(RK!XAN<|Fl^W8!_j~=@lxrK; zx728x{D1BD$99&It=;7ma!<E<R~~%(qgvQJ$<&8($o{A|ia80$`H;)`4dh6i|G>V& zXwx2yAphIQe^k}G&mez5{SEd^u}$Rsl@eaPz&VFG=MZupkK*X}Z&6>5G1no?arFe) z+iDoOj<h@2%e`LTp!hMYL%Ar=7GfQBY-Ugo#EsUxePJAAvgtF0^y2yKX*OAAWwW$8 z)tqK4)_S9i+r4i+U98orjgMLGY|da-gO%;-r>4y&o9J%yP&QfRLH`oxclFfIU~$aA z9JA@L<;61}X_zc<eLk7XbB~2|`ZSwbIQu>`EUQ+k6srwR$f=kt8C$chm1+$wyHu$< zX31H%O*W?`Vu{)KoEA^8siIwvp*1@_O}G|kv=X09yiV;03cZOT_`N^KK^^#F095=L zBr0YaBr4#^`^0^A2l3~)AF(<pDjYrlzKF=n9-hAl4}7mMe83wZ7J$DMfWI4ne;9z5 z0&qJ3|11Fi9C7NagPP=LR{_w~)=Dr@hKWmjl512QC@ka`Q^|Z`aejU&YZQ!RDxWRz z<qW^wX?zHda9^=_2qk*YtXuZwy{YR}vKmdRW}aJj@Dkc!uG!Uwv$7Y=4Fm5sXC(JH zj7KKl3@t<i-{Xk8XX*m@P2@uO^TH-|LfC}A;K7*(r?ZwaAq=YPy+yMEAMxR@349Lm zmt+#ur-V&)WiJF}1TOP`Am;A~E%QtKoX?+$x#9Dd_yvLc`IH6j=ktXJKPGHaH-+ub zb4TF*JWo8hcR&9Uxc?l7abHN}K77q*c)kLc`ylbC!2Nt!06yW%b4}!*61boLn;zV| z4~D=cPnpN@_<PS6wC3fyQ@n`Uv0Yt}mTlIGnqyvaKr0uWB4`(zP0(zMCgdL1PJvdk z>U9&})c+(5^AJ`47fwfv<fiDuo$bG?gdN90Utb-ES1RIh+)-Q<|90~_^534QaDGML z{xACzUtQtOb4Z)?t2ij<e~pi0ER{;&@XBwZ{yi^<w&XAA>4=dn-#?mMz7u^fOF(ED z=heb>pXab>=qKSwb&ueX_2vE%=I@;nJ)%QF`O;N;zhzws&|MxB&qSe|bQIbj{|`cZ BQa=Cy literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_analog.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_analog.o new file mode 100644 index 0000000000000000000000000000000000000000..6d50f893dbeb54baf37ce7cdd3f6dfd36210bc21 GIT binary patch literal 1464 zcmbtSO=}ZT6us&Ak)mJ?f~76-EmT@C(<C6YrHd(1qfn$2EsBfqGI?o&lbP`5MIv3; zg?~VB@3#H|m&U&!=-P!pK-~wucXD4k3~{4(n0M|w@7(h~U)|lkH<!zSjU0S{)1GAk zhR$j3C8-DVkcW}e_<Bt^U+h0V`uHBi>(2sCevKV?gVML-qfaMO-3sV$SKlome}!tM zJbO^Rt%GeS%q_@b?mMiL2SBq3dHfe;5xi!RYN1}MZHd+T!^h%L6a{`qc0<vQv@jhd zc1nF6wYvdk+V6CY^36aivFTPz)pBLityIOT)V&gB<+U~9-HM=*O1XMF+2mgvI-@i2 z^Y<))GxG!i9Q<a5gHGAFln}FSf_%<q<xoJTkeb&z(m@lyz!fWuHxMnyR07-BlD^F3 zMaEskS^B4}_gH7=4Vm9#-ugjH`Oh0NltFap`fz;+vgJPry9OrQzLG82xl?P@m8nJH z3#H?36duT6pr(qp(kk?^AID0YMqg^#n-0p>zKWw@V6ZGj9z=nWhYAF*XBm%no^yf? z&X<tCkm8?kPWpU`2RDA%GqQ<j^aMLL(<+dzQ9}c6OBxAoGmgRaqh3#iChhSbxxiXn z5}eC;c-%kE@Y%at#&NnUFQfZ0HzDpbPyRHI-TNZ*H<{1A=n;=+fjrW23p?cbuk{tI zCC}-*!kl81v;fZ-E!g?f$Xm6N1O*HB7|$b1e|G=$cCu?HgFc%cQzsR6UQ1oZWLEtK LlUr8En63W<+zpp8 literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_constants.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_constants.o new file mode 100644 index 0000000000000000000000000000000000000000..55e9a6eae14ff4d89ae78df723128e28e3e42624 GIT binary patch literal 1968 zcmeH|QESvd5Xa}5s;&Ca3WCs=Efl<h7cOaqRuFQe^$cyz(L3Ql<V<s^IoeB(WDEAm zM?Zn@1wVmLKKcp#2!db1PoTT)47WE1L49>!{xiSXnMpRgo433BPv&YhpizTQF!hK6 zOs-9B@6z;O5f<P!;#;UUQ5R7cP;a1KN2PM}=v%0Bs8!E^q5twHE711+N21<-_FVMx z{4`FZQ6`S_LdY}`t;VFtk4LA<D&lk`lUSY=iP*N?hTC+uZO0Y$s2Det)m&fK+;)VH zI8FEA?;k>czj^rnqiU8_xx)Y~pszohWvNKjuv7;=?p%UjxyBaIuA64vRpzo$hxXkX za@xPdH;^x33F0l}_ZSb63&vj}uQPsvyvg`E@-4>SA@>-6kNhd)ACPw#|A@TL_-Ev= z82^GiMZQG~F-+o<L7Zo$j51l;F{}+?XV>2wv^zmKI0(Ce=?2}<aJ&AV;T`r}!|Tm> zLAYtef^cKTGxLJbF=AbR-}H7`hS%$xGY^%g-$g(6K{T0+vey81c|MlWky2S)X-bw% z-bk>Ak&M7TDoe17{K|>*@i@sOuG7EDiYlO&n(k4m=aIpbJ`3ShWoX7vlt&Yo^8EWM zuFu5Z=08xmx+XvAo??1ju!g#qIX0D}r_lMJ*f-33K>(G?naX?XsUE^5RQ<owy{SK) iYyDs2@2(JZ@XGnB9b-^mLd(ji%5UJ+^q3~1^8BBfGlJLv literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_digital.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_digital.o new file mode 100644 index 0000000000000000000000000000000000000000..0289c8e751b973116c59fa74a3d24d1f74ed4753 GIT binary patch literal 1064 zcmbtT%}T>S5T2T1>&>5w;K3CHQ?N@C^iWTgqP?hxqImF7(qwCbO;gep>Pg>9j~;yi zeF_iy1iI7g(6HpB1Izc#H#0jsllJlC>~yJ80kR4_!@?sKz+PJL_MEn%4mEhS`XAfO zdZ%Oh08c&CpxfyjF}r(l#V*ry6hwYJX2UdNG7{{#ImyytJW?zRqF9PR-e-cfxYzU? zx5ZtL*?yKZ6>}O5)Va$r;yT{p;$3A7XQ{&XPg%?=ofN==!mx!xOGQjuoeO0f!+WY` zI&3Iqz0j93wzQt#hi}f!);iOET_c1dxa)`UZ7lr}4`6o&lX!fdh61#BovB5V(-VFO zz^4z1^al!MmSaRrikSo+`qBqJm`;HQX_APsq;~&BoDa9OY+TgVKF(P*+5>4jieSC@ z1tLl?(EK8MDvrDRYyG~e#XB8!ibnl!ilXAwzldeOsyAKtr4jd2QwQIQwwVL0C^X-W ap%>lYK<5!qU-H)!DXag~iRRzPtp5cdoK}+n literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_drivers.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_drivers.o new file mode 100644 index 0000000000000000000000000000000000000000..aaca6502919044831ed2501784d6c3b26ea6a817 GIT binary patch literal 2704 zcmb_dU1%It6h1q%X;V>&O$tIwJAt5WF~e?jq1%_vZcL)Gw!y5vMA%Mtr|huVpUzH0 zN{}Y>MUX;53;Na+6x@Q~gP;Y)twJf(zSJN3BE-@{Us})-NWkrS&dfc{?Cp-ec*5*C z=ey^A=eu|2-kcfBj4P1{utnf&*vc3MnC#t(4KFlc2YBGJ3b1SftSDe?4#DC(Kt2Y^ z8Guay<p%scdS2^=D@`@`TMyQ*VlBjsBsNO47QSz^R9Jb~Zh!n4;;n_NpRe{BUM=Mu z@6*&@>Dh+!uOdE(^Y5u}@KS)|cjTZkfW=#b$Z-UEN@aj-6ZODtYlFB+gIseiP($PN z1pEDfoN4UWvj=v*jL#iqOLr4{HgP<P{VoEWd^-x+YuHag4Y)4@7eOg~p`wQQnT>Q5 zR#Y&OXHZwF-Oj2}ino{kc-+piwhk_(3s>a7xkx|l0drE!Yiccg=k52SsYqi0_i{<` z_i}w&X{@VoIR%jT2-kE0@x^D1EBkOw=TJvKazt@GONbqT{?Y@~v7{KAYwE7cbANsC z^Wc1aqrMHfqPW)p7n+aTiA5ZLG?i*Vac*OMI^Ae3{OIjJ=^?xWn;0EEtnHsT`mUC( zR%i1?)2?VIs*dIsEiE-%bE+roS&W=~(RQu8d&;r2q&_k{5{oDG_=vXObjrgR#SR=G zT#sus5|51}P|d$s1jnNAXS-X8+Vvy=sQA~-RAiE^&jYASr}bm11o&fO_@L*X<{3sj z65!|KNXsLfbDn7k{8{v5K?N${DU|Fj%zdq$1II&fCj>u>_)hG`>p6ru*?D{juX!0j zQTR&&UlaLH!ha+1FNN?=1b!2JH=R(h@}*qCvF9wOuIFKB-a`cNX2o{(n(4TD42B9I zQ1%(C0yb474!xR$+(hPBI+e*C8y}w<%jUAFbY?6EIpTlaqtDe{WRj3-&Fkk^j8;!o zTrZ!nTp#kXal2CR)AZ^0?82mtQjj(XA2rJs)LkcE=AH5v-jDmh?~)LH&xCVKIDZGb zB%J3a5r2*fh2b6G8R5^1nA{!_@0ED?y~=%G6ZLZ6ObGsd2+pgP`Q4EE<q-T+fy?^8 z3aP&yQokl}S<l@No+$1YnY<4J0+;nnhSVPqssC2svYuuL&+QO=K=F0%#&Nofo|s-g zU3SeG(D5VmeUT%_nl*LTns-4jn63%>OuY_zzFIC@___Z-rXdYU#{csjW{B(!p_>Q$ zI1qj}dO8n=$l0xmE3YQz6F>Fg^YWr7d`aN)4gaCkSCo4k9Fu<qAL0y~A3S?h&;2PT zi{nGO_?!_&#{H-L^vN&Pk_CM?srLoACJMLX9J&*@Kd*lWVzPFG;JUbEexW2_+?Syj RFz7bFPc%Brg~H48{{dVNbn*ZI literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_info.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_info.o new file mode 100644 index 0000000000000000000000000000000000000000..c9b4a9d8c649ac60beedf229ddebdfc2f9fa9add GIT binary patch literal 9928 zcmeHNZ){W76+iZKLI!CYNPs|T^8%rR6ugjzHjY;D@)yuj$bws>!4y08OXK=qupJ-; zE#8JEBtXI=AF8byMs3#ywHhBti?^;s6jik41FE*F+Bz*jC$%b?+EUhfE%nZM@7!>6 z!L2l@-+GaK@BQ6#f9KCV_uls$MmxK^oDK(w;((XnMo*vs8<yQ@8&=bR+u=599R@IR zlUm=~HM;g!oO{>>>9>|4M(w2l8OPjoucNH?x1#`IeRAJ#ge=LIlo>e<j66WP_cXwc zD*)bdfT}i^;b|*_xd6^Nh=*@;fH!!~*X-PD9O(z=fpy>tU;L`z)o~v2(R`|}?|EhX zx(1mt<h{DZG5)FMJYItQH4fNuNCPj)l_LLp$iL6xcg?}E@C#1x{vP>V$p0+3kiXR8 z&tkjZ1wXE|<ug-S)$wD9jXJgPmh6$m{Xa8~U<}5NzHwjklvY`PbxZ5`^*v{vBU>sV zJ@2R!JpU~e7Lu>@xxVL*mVIYGIP})pmCt|j^b6-dDZzM=t(6$BekWu;)!=w7+8J;f zxoee>pFioyw3QhnQ`-FFg@AVIy@jsv%lAR<QW!=G_d>p~4RVD)!3fz=vjh?sF;=ZO zpX3GhbM!CWX5^E|pKOCn4OD)pV?4;-Yn4X+`kvP;n_tz^y_YmchV+a1D%a%of|thH z9Vq)MWN4i9sQk4kM>&9FhifqpFi&uuVNBI2Vq?eWMJqlOk1Cv(MtiSqbB=!&(8d>5 z7@mCCHU34iWc&dKG@ZtEwz#&n;duLaKHPz0of!W&EMHC+93Ik_EjUm&j4i;}`0Bu$ zEwp;lE@)bW{2t`E6YC__i?RL*)}D6ARHIL1&t<Lhxbt?*Un?Hf^~6IlHp;>4a~htS z=d~S^*d{;c<0tDh^0u!qMi})kY1Q?FE#Nqj{_0sUH@VcAsnH<(;g<z3tv&Kt@yS-e z#QhbpHjV3FgL~poDdnvd$IO2)H?H9a3?q;E)k{7s!MYmjYP7vYGxB$0e;IzBL>-PQ zBexDJAEWgrfA%5gFDM6`j(Vstaz`~+c#j74^_UCUUm1C_nQV38*r?`u%;5s>1lmbF z#7A6HxULtq>f=+|Vk^J0m{%I=BVOVsS;0+ui2q)k^VD2ei~AurhH|uT)APXdO>0QJ zI{HL5JQar=#$oKKxRE2Bf5(00LVGE`Y0RyQXpe~Tvp9AU_Z99*%SQj*hG!k<;bWD! zZc7c%)B;%RzsK<SmO`esjB*pk`myiF7;2+?j|3*057d@x2ijM_+-2ti&7(NiaR;73 z^^lp+oSFW|AxC?q7VYz$abzyxeh9XJwSK+@hDXQz^e;9%#Cs9f3y;{7WQ)JemKjC+ z#Qw_8fr*RSB8=ya@m)A><tfICWNBR}zxpvpXnnpwJG0o%p)I7Nbr#xz{bQPAg!*7W z#*cltviH}8fd1wb$`ejC>9X1`I4SZ*<o+FaHfHg>YegNTt90+)Ba@T*foE_pb=?66 zvWUHE*gn`i>9>dr_vuNW)5b5Ozu8%E5~_^66K$qknJk5q<WGqU=GIiej%Sv@yw@@B ziI3*XTzI}rjG~?E(C?#||MM}%(SH}bi;zp$>%pA3if8+oHY5Ll22B&CF!ycD5r3oM zF@_9J5c3egQGeR$3i}$t^CsRETdx$FDF1v?>}hRUuNEe<h*5kU_;I3bwdlXF?RFgN ztTuB0`m)e8Fx$wzromcsHsmfN?yENPM!qodXKd44u|8t%OA;?(#0%(e{wq6oX%6Ks z;dBPjm=ERdN1vz9uYVR!rjh3~-AUHITXa1AIqoNEKb*lhe5PsjuN2Yu57bBde-_@0 zfcgp;*C?I|w7=*+Jj?fC09<nlpoI_N9a4gMAH@5x)VdE#tozV`ZM-)#wI~nRZUwOJ ze!#sZ-@jMqfVDn-2jP_M6ZYrOJ!9XEWD9+8Y{v5g_dWKV4$#rr{-eH)o4Pi)=v)1X zSSa>rt-dL)2NR*4W<no`566P|ozR13Ancw!L%uVSz=34IAERm0QhL;k#uFhkxk`^A z5zb?_q`oT@iRk^N9*TuhA%7&4G=oTK70Hf=X#R+95`BxlD-lQXLDL^Zdp34_qkJe9 zh$j+eASLFs_qNZpdnW%4d2jb4Iy#*U#bdMOxO|;FlIzQN*FLy>HybAT(Lt^+59x#c zq)s*s52f_YTkY_SxTPqoVR_sP*51O;UW@?++6rkb(Xu?KZ|iE^*xlLj({E;z?V=^` z+T7dT`QY-Ty~H#8-P+o_Y2&8#EogLfC=@YQr$SMamN#GqMPlH@SUe>r;|farUq8(s z4AQDg^3(b-?-KEN)XJpdBz9z^`JKJJn|oXI4m)Lg%tUBtP#;eEA2rc~*gzx{NKxvg z26ewalrVRO;={=Z=2vVuY9{<Ca_UBs+L6Tm&Dkn1i){Z){p*K9@o!PP<o9&kyu0ju zmedpGj^R+k)Ptdc0W)F7Qo5PM)$^y~iKNIVd%tap_nJHH=6B!UMc~_y!20&~7JbF~ zO%Lndcsvpq^oL^BMo$fzdh6<;M0@~`8of0U7!0NG^d816_P85YH#V&CxYso5EBuM* zYHT&ETuHcljZPzL8XDJrz3F)Wg9|>!>-grP-SSNwK*N8xDjG7W#d<?8%2T3>LxqLh zj1#N@J}D^0mcJRtXBpI5%6tILJkOTD*-m`VLHQfFXf0=4^eJ9c*5HTa%d8&7&@Sza z<8KI75%Sd0V3rL^-?lwB<3W^hNb)*9$cmy(YZVBvpTe3Ocnq5kNnV!FVCI=evqtbU z4`+xX{P-o~w!Hu=Sl}Sz2KRfo{vG3ox&H*$f52LBFl1FP;y3ASVAWMzpDiN)w<7ol zMevWAzlY<vom1?qBJw4u|5kRE7r`rw;ERjkKPZBC6~P}Wg42utt?UdTPVqd!spUgI zsXWej1t)@7$Nh{OjEi+Y#(0l{13eS;g<=D7cL3^kLtPMp!_nx7{geR#d@xQyD7g`z zWZi2$O&;K@H`pmI+-amczH4JFWhSf}IbinUQ(XL^c+j*|Y(x!7TbcEQWi{I^cCvtm zEyx?$xxt_8jF?fp)djNNOl?Ue@R<<snL98v0z=qIb%=R=>$^9%wRZPy?&{jo>Fx8j zwsm**q3N+?JYx0?r|=L?fN9Mcuqa6zc?4v!Rc*nid+gDpCnQseh#7-GB5+@0yFU^b zj^M*n+b}(8ShKrAv7jBEwvk6d!Jd#ch0Ma4sd)G%p-uj%9Rzd^U6H740Kcs{IM!=F z*htZ(=tu)agKVe8^f%?PILinW?Yk6Q<eVyx@5feA<(Dw7?h~Ey`N%Ig336ed%AHu_ z?_<-Yn{nddl(fcr7$+VX-_AJMBjX1dC;mm#>;Ty!_zA{U{wYZwf5VtAS0r5KFXQuv z^vd!TjH~?O+$VqKTdt1f3BPMvE1t^|k1W56aSzJhEy*`9PWI3pD9Uz;U*rId`6PZB z&q_SCf&}a5Bz&oazs$J0j+2b5aX2f<%XxB6l9%!Gl03yhtm_3yUdBISoZ_%dva^gI zbwvF4^H{lr%ki&ZT#a)T<K!3V6+HNxsa4eYFOm33UgWo4gnxy?FXS7F@Nba#=~+pX zZpQCMJ7v5_;;9qDSZ`-s-S2}Ezq~FH#wiXmo|fe0c<z^QibFH^4@x{TewcAJ{wEk$ z?K~;*$oYJMak1{FI6wX($&+4zi-S^K$8shme`Wp(?x^-O6v3N{@B|rG{T*UlwI|KE zdT#75!ZTKc=V=M2XJk>%6~QksuC99pKZlW>@_DFB_&tIg>m~^ocM1&~5?&|CdnH_! z_c5-<e~@vp?(d^rR3Z{C=jRaP>V8QvF7~_N*~_@PUi%nV*Xv*r{xL~j_V>vm^3O~1 z-?v?|zE4T`3JITNT*P5F=l@y8g<k?cC&|nE`n)7B<L^i~?V}CM|1RTdJU?Pwjoasp zt8sG?DHg(Izsea``70#(mG)HYTW4IvLD*?9uG-Tf@yPdSkA%ziL?r$hc_rc06z5lp zaS?xk?`B-J=LF+wp1;gE#Ygt{Jmc#5a6!VUS<U<69ma({0)Llr)t)KF)%7ap_Y@K5 zGR}tz#?|$zVqEAI^7wa6tEhUHFs|yYV_fxjg@lvI^hX3LtBUY9FfQy7@=c7ZdVeVK z%j<4PIO%P$wBql_jH`ZaU|i@G^4${8jC-7M)gCY7YMgzNynN22C0x$)F~-$+J|W@c z*Zb@j{!P~^s$W^gg<nGcX~tFi>&k2%!t0rvD)Bx`_Rtl?V$i`2u`dKJ-gAY#cn|in zzyjtGxKKs^g@ye3h@TI@og9g#{QX$t%bisZidMpm_}wXUcM9A=f65Q;{$vu|i8ysg ze2u$Vbio}6MD1akWJ%z3cO)M0M{qD6wcdAy75{&&<5YCP@<C=XxU*dZi2L$cP7uAL zQG5;j$YnqNQIkru{X-zk!8Yj;bmD#S9>zuZuxphkg`fbqCJwo*!VZZRo6qW}r;x33 zv4774Xp}*0XIcNp3b8Ot*kPb7wfWe>mR+9UMA;w!uEl%-(>Tpn)W8(a*A-%Q{=-G) z1O7psiYl-6dr;<9>o>X7nhs)}X#Hrem@jY>F|uErKiITN8SCFB0Io&c<XUmjk{smu tJ-lEPj)nM9^?wgBHFiXBiVwfng(3p6C|&xGUbme84*O5Pqsm2{|34Gcb)WzM literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_memory.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_memory.o new file mode 100644 index 0000000000000000000000000000000000000000..9f6725e855fe47cca9e56c71696e73fa53d36ea9 GIT binary patch literal 2952 zcmb_eO-xi*6h80WLE54e5rGa<c?Q$!q)cFxQo7;6Xpx{zWTvr+3wS&p&Sd`Rn`Z-R zWLnde8>uukX%kU59ab((+9tNpbmO9%lGb!N)=ifJQZu!5dd{1B<!1Ov7ro@YbIy0q z&v)*<?=n-zPQ0Tk3W%Y=*RXC06yW{~>$>i$I#j_+sLc&7u%QRd8vB(V2H)2<1B*ui zA^=%;ZtcQ%xitpUD`6$K!odH8sdKAm)Le%TYU?lh!kA>{haGUL8I<@>JZ>f2lUqI0 zn_Ii^<5!eF&lErTfvy*zMla<5Dc)tE7jB~*w(AFeXLWNA*<Sx+#^&T$P@A7~BYtZa zzIo2&3354%9Ei)G$myxca)r1j_bgM9qgo2~vWh-8R3(1M1Ch@!`NDbRIj=(egaVOy z?1_35^`4p`j6aI;$B_4Zm$%G0OPoD=A%rq(Hz4PF<h;i}4BZdhT*zg+TqFDRPZg|} z$2iJ+q#8QH)o>((oHWEU`=GXy)?9_IYrEjcb+w_YfE-yRoH8#~gy&Tj|C=#?YZXLh zSCr}5!%!$*hM&)4-G}IxXI}r!PAE|BXAI_4Pj)enIMpO<IE36QVYj){6ZYaB{8a&W zZ%@IudKK;o_JBG3Bk0==`f{l5hPSsx&vnDp@>ysKKB~Fw?S@Os26%&%b3fK>LCk=C z!9G*(BD-0Er4sgPa0p;Y_<Ri6MFV_6vWoy8kWWtr`>KPth*!^Lm?ocm1MLUQxccib zee*E!f*AvO_o_JGiFI-P3HvDC6vqAr7kWFd?DxQKg((B?gEDZdQ!n%^?7uRlHpV9w zuX{6U<G@q3u}YoNuhDu^EUvTd!8Ps1K6Di#U*g)*I?t=V_#@`?CsvCQnxj3Tecf(P z8_?&oVzGhz$bUOuI=@)|Dn8U_9X{|1y|x>Dq0rmf!M=Cj(<13~!i*ZRls1;OH79Cm zJ+0$*dMuVe%{HSk$1<IBwxx9if~~=}_O3vCP&;VY$yU_b4jm#q(5}%;dt0z$yQ1LU zAs$%5?b<llrZ)@#!@tc21J4HdWf$3aQ`I7_O8LdL)xz-_o@s{5Ajj`;`<}`b6bvfX z4X){~+=zz|S0sPU^((y?R7zG!J&8hakta`Yfe&wipWOmaZGnG?cr7v==S#g4Z5p58 zvl$;4waoZX(n_Z7$$$w5CLn60MibUaE7@l`;n;a=9XM^{5n49~En^f8j6x~+s5R#1 z3Z>7b99Qd4jiqTaV>u+u@kz)yc8Vkw#R^!nKNWLlQ603-#xjm&A9o4ZE^Rnk63~Q4 zVHej)BqY3A!he%+*<a&FiSo$)6B1rJbEO2oNVx3(hlI=iS$?i4zr4;@x4>t&!0$@< zZmF-w5-#T#`@9G1z9{)SeE;{B;S(J9BECoR7vB;6RN$rDSy4;icX&)AmjV}l5Xej> z9b*KgW0z!9XttFw0**D|Kw#8x3<!*5G7xZ4vPlcr=|CcF8VLxP>15KvqxAm_4bxz2 zu%j%U&h3kQUBvYBemKyCl5Q!T+d?exgi%V4gVvE$v7Ta`UgLOK8Ms#tpdSsMu4Lf* z4SXnPx%+>Oe-mRVXL<Yr2Q-|Mhu|-;c2qX&{~&if&K=35+f&4g{`(Q5`fd2gBhTxf zkwMf&|FV?NrEu5zzm7b2q;G(}`||pPm-kLNG`@ddkRc6GS3vYFZWcez3(*fKd6dWh E3w0#L;s5{u literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_spi.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_spi.o new file mode 100644 index 0000000000000000000000000000000000000000..41bebca0b65906e729862ef06329be914cc338ed GIT binary patch literal 1512 zcmbu8&2AGh5XUE3K3V~yMLkq-zz2j{iL5q}Dz!bOln{^r(I%WY1b5?fSIzE5UPnq# z<Pj>Kq7Q(?m1jVL_uvU&W;-U9$q7bsX6EOazrD8evGeMAy;cKjHTVLH%u;~MU=g>g zunnuQ0$+o{kB1`oZU?~p*kyiRgZU?9-%w(MdIF5=IFKV-aI5EP5u+Tshll%OtNZ4i z=oiH}PGp*kQK5xNlsITibTLZD80k1kjf%}wE3p^08m*|g7dBgBOX{qFQMA2HJZuV@ zX-2J`#W(s9oyj%$`OD{&2TM<kxN~SuV}MG&-LAm0lP8_)emUGla?e@UDsD1g<Bk>f zf;o9I%b#FOI#ERduJ!@Y#@uS~ROR~kOZ9Dr8|+8um(|aZQ~d|7v-`YYKJhpVReUxm zCutbNqZwfERGp?d1$|W-@|_vpcz&w>O!l?ROBtKA$YFLgRa4bdnVckrR(*L^)phdW z-&I|eE1kwYl@H<B>x0&yXS9;p&fw+o(F>Um$4a|Aa``Ur`#xUTEsn{(b@&~JLs*_? zMxLNI`pPFZ(rPS2qh<!ep)?Z0ld^;`F0xGJ#?|<bSYR)`t{a|4n{$61|1KY39o?O+ z=Qh~oCmt~%eOkx9FM5w;k8u$9{}G>Qa*0u`YxGV@^I!X$*h`vrpBPqV*MDyTd%M2t t>s}3|Yg{mAe-jxE|NB>w`FlqM7c6>7iDPzMi`Fq%)}Jukw}tHe{@*08o$~+y literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_spi3.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_spi3.o new file mode 100644 index 0000000000000000000000000000000000000000..6cef5099a5e88d6f18fad4cb8483cbfa6cc418e0 GIT binary patch literal 1496 zcmbtS%Wl&^6upUgv<jf~u|VyDkwB<L#Il3BXvHEBg|I+KkRXa!6xW`_R^x~4iIl1f zD)9v%koW}HBe6q>Pe6h-zks^xB7%GE8Dfmtz>OyN+%xB%8PCkq&YfG;N(EF@;62PL z#R9z6X1JBY7R<vOeAITnUSQf6H2@Cp=ec4%J^1i;s=@OL9KJZJ!ST{{SVYZdw0!wZ zTe@;oYaLGyKE1(unLIU|tKvXCYEs=YbldGMw${D-fc3+0WV@CZut69z;c|AP5yj!a z8zG8q*Av_p<CwEez1e6Q=B92o*_svm4MfKJI`O*6XvQ>}8|jCY{?VD7fbT!bCbiNN z1JLkS78*Jg<7`Tlojm!REXtvd%wld`<+vhwnx~k{5?sVgdM0bd8<M9?aWzZO!K^$a zm8M63;Unb9|4FLC%ai#T<}x2}xV^WNMBX*shD#G5bdwLgAVqzih!k`tc)P)n&*uBF z6(p7|yfA>ty)hs29`~)t4P)N7_A+5R3<lm1ul=DX++M`FlbHq1pWR&^@Yu6^JaA~s zx8=T9@hWN(Q`(kz1^F{Mp1zxc_;VS|{`F+v7uGK5iHNi8DirgPr3*e0pgWeZK;KOg z(CyIoc_8v0|A86y;+Ei4!J{SX;yT4UT16ebDW#WfP?t|yofG-fI_f>0m%_`EmvYGh zy!(ZI2jr0tdWYosul*+WlBa<qA8P%_c@nW&KcA}w4V85%aAiJ?9F5}l&m&jdJ5n%_ Zrmv{Tg<4lp3kb^kw<WoygfbWVe*)c^ngaj; literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_test.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/deck_test.o new file mode 100644 index 0000000000000000000000000000000000000000..b7d44112cda4d1ebf7c4dff815caf24e2ed687c5 GIT binary patch literal 1936 zcmbtU&ubG=5T4Ci?GKgODu@-_LzNcHk_44TJZut@P>i<Ncq)=^H(L`-vSssHT6$<a z>!E@E1)gF~-t;8Jv!{Zd)&D?yDp+)8^IrPc>|S)j^3D6^n{VFkzRhm7kc%h^h*01? zoUQ~5Fg|pe8(wO_D2%|#&d0YWDzuNr;P^<5bkkrYR{`$8b(m-&9*r5tCp(`y2Wsi7 z3b2Q*dp}gA3t$|Z0Bv0F??xag>uzZ37jcn)WT<sWGg8nw?9Bn}hy9f|(59NwY8_(j zm&c`*wgNA`HPwVK)-IE$*l({!dxoxozTeeJ&(q|dfS$;Eo+f$%deYkOd9$f4=Th^9 zXQKf5Oy<5elYjhFD>_cis+iS=w&u7RtJqp9y6!q_)f#55RjD%DVjHflCG|u!5sN4F zctV>o-Fg(W*z7FvdR(JQJeIhNn-2?mS7+eopP;%L_$C2V`~`)IPC=o9^zymjf`^0r zxW@;bAewu2z<v^$32C22uFw#BUYy`?FNDvA@Q;uu{}n`vLJ#0MVvv6WdD6e*x<!sq zwyhT>W;dB`!E_m>w>*Z3?50_RQogW|P8CWEx!h8=SSqH{g=`5dr_pq3_TmP^)8K-= z?p7OYt>3w1Zrb_9`GqBBqERZHfx2C{*0=kDCur}uK8?4d+k9V>_^9Q#5R-U3lKq(D zSrYYQeHP#W&#(A=49-s>e_qmWN&H2Le;vYiIDZX&Wc}w5{kIVQcZd(@&FwlfR}q=p z!-~jUyJqUl-eRDaO=g0=+H8XEI<z2pT%QBoa_V)v!MOc@gN6=xs{<$9K+X#)O5s0) zQ&^*~(2z8ge&C<%Fz-Ky9Hqll#JJi6xP?f({|h&KbGh8piky(n6?y(^e;j*hR01zK z#C-YeQC;j`Y|lWBa&e9^_2MBHEDM68=#w$x)6lZR1uc#=cLXmnUpznJ{P&I&%y9A* YEu;{01$7CNp#B5?*E%nR9R2-&0cKd+$N&HU literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/eprintf.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/eprintf.o new file mode 100644 index 0000000000000000000000000000000000000000..24a9c03ad96d39fcce2611de37ecdb5e63db38af GIT binary patch literal 3896 zcmbtXdrVvB6+icW7jPg60h*Wu3!8x2)EN%XU{_*Xn?NFkE^6XdThkUB$0>yH@FS0k zY}{<sG&QLd+H7r;X;3YZdi_^6r7A3w>P_iOZKbK{QvR4GLuf)Xbqk>syUg*<@x7N^ z4A~#shpxZxobx;H^Ie<4mbO-&<3L*+yaV?sjSDck`u<r=A4SN8RgfI`gPdeAG`o+J zzhMxW<)poH`+0c-z?thj3>`5+;k=K@amHJXAni?b3vz;Skxh7B*b0dSPWsGjVSn`> zE!}5kMcq?h3~%z4zjtnm7py+m_>!;Uy>pC*%h5wVdjsl7eAD%(bD$uU4NnYaL$&i> z${k~yth4)^^4xxxJnw6k6Wu%Hg{@*DIq?2lQPzGv#@1V31gM)&rs_%mPAX-jSpJ23 za^R2Y_$lT&jGtol3UIlp0%nw)xJWHXpM4~No8k=R7M%)xH+W6Ty>`xwm|vt)?)WYK z_gcPWcl3=n?*0tr^Vv|)abo<u>)*}STn7GBhroXvJ=9?z!5BP089zVxFw7L8?5%VT z#w9r<2d<`Lhiqvt<xM&<X0&QKF3Pda*p4CS^xEfHk(F>?V_p<1Jz9QRe@<q>WhGbM z`YrZhz626wLi`=dw<inSG0df${9z8HUvVOOzUeeK;}f9ZB*uCg^Q9c$<yrUR9Jt@+ z+3t6F2z(9Tp2a#-yi{ZCPvA|&&hzW@CfJ5Zj6D>&m`c3{V9Z<WRSES-$#W!2$rEGx znDlR8uD37`&7K8)lAeaA7%0xa>vE-dn*<2lU|{_e<JpXI7sd@ISV<G`-4qYagH{`* zKBJ5CJB$6N+RzNpoGyg2<OQse1w_YFf++v6SR9*Zf`rqA`!N`kOi*XU`hUat$Q&;w zXr|xJhM{bLhiFC@SXRV?xp<i9h~+|^`78wdIWSa)arkmX$6yo!+$LqNE|^67Fw#+! zO`t8wB)-C<y)r@Rt%X~+o#K_E@C0FTp7MBs&m$c5UQ8Jq{)Tw7Al~(2Uxr5^FoCu% z2%_Unw4vaR*r9k`17W_zyka<a!<V?g74lIC?hmt3?+h0h$p!aEd3b)E3vhUj9TUf< zYauzZI^OW7@54|G`?>wjk6$r>m^3&$N{h=Zr5CZ@24`6*^^tO?yf<?8QpzF5iXvr$ z;;YYM|EV`o!Z4Oc7z^86I>Ag<5#Jl6XK+|bah}gkAZ`-*q-%lAr3S;6QjW9#rVVX8 z%^;6zI$bL!J#(r074Ltj1!v{M^c@=hoD0NOVLmY~;KbUD7GNH>`+0C6j**{F?<uy= z;!F*Hg4nw$w>^7l&L+U#pl{DisxHAy5eN2@@^G<@c^2fmz_i<wO4Wad@4KIpoeNmQ zJ1KYZnoOV4m{uF3n$uCjd$<5BU|&w7|9_%?wp0&r7Pa~wLOk_`6QQ69An<ZNxc{v7 zhvxGs?9pq8;mQ^Hnzi@kamHCm{)tXrNpiI=ntTf7_Ek$`(CYO&wO+drGlFww##xFQ zz<qpeyx}UwLHGVw=);Wlzhc0-$J)hEz6*O`#yRug%$Tu0Cy~}_@wsZV7HyibUu8Gx z{azF~sPZd`k2S&?yRCShV$8|}X)odF{?R*v=0ST;roRhxv+(OE-XDYLxQOx4oftXf zv6Jp%jdGUP;Fmi2%lMAGs;d#@*RPZJ@XPftqkLS5H$>H%Y(Sk6jN!^^r6yD#@4S-d zGisi*_prB3VgjP}Q`C#!q76O$9MY56`}BJ#mvEa;nKCd(GU(O}x*ci2*)ZemJdSZ| zJ&WVrqrARAxq$Lvl+*k412z6Q6Rh8&{3Vo6V2owy7zOLkm(XDS0O{nwC3%_&L;t{s zeka^+W<y_PNrltfm^_^?72Ym~#8<mvY<drj-QLzLPd~Clp3Gk(Pc|cV8;3M6$Ba_r zM2XZmX_gvqluM0Mk4TMQZj~BuZj%~s)go<NE8jHd%k<tz4*Vs3=c}q~YU}E^H`pCc zSM!dRR@m9x{Fr6S&L2E!argBd_H}x@dMyY0f|hWn-{P$75B44GI*g~Fud^%c_l1uH z{T7F<rn080+F`4%v25`Mdn)l%_2{F-w^dt6Qe9P3k6!=FqTf;i%%oO=Fj(oA768M) zl@>!wnJX{NSZ-%6@_C*8sH(VL<!kh~%CAuQBdVz>l}{UkEFGmBx2Ct{d>isP9e$lo zlL3A+W~@4-3sK_?uLvj(T94sF{HV(JsIHokueV89T0g>PCB7H=WXED46u@z11Mv3; zyL!V1Z9b?t4qf3sZ}oO%t9r6G)b)I?|A0zD#Q`|b^?X+t`umRggWx}^XhQqWwmmLq zTl=2Y)_pDRcDK{j*3u5`zVHkE{&vm2=B`*h6k&Z=X-wQr>Un(z-=Ov(6Te#JXX2#? z;9q<IUK=s8pRbF@ppKpc`TBagAH-KjvIOyKbaqaw^(H>e;^MM}Ug!yXJHQqS2bH~3 zI|coRy|%Fbco=L4ykRfcIzl0^1^X1j*VohI?+q^+`u`3VRL9VkO{9oCTCc0|E7a0j z5U&IuN?pW9zdDr*30nVhP)L3>bJ`p{tnxE&`nU$v8&$D-*7uMg=>Mu;t=d$t*P?07 zzrOb*%nZw+>Q^mlDu-zmxIcqWHK3*6GkueMmwGuasX#JEbEWy$>PN85+>r(GT>1p) bQntlU&9BBNz{5)V{p$a@E)A&enfm_$?~B>u literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/estimator_kalman.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/estimator_kalman.o new file mode 100644 index 0000000000000000000000000000000000000000..918557966a7be006a2dc372b37d901723bc6d3c9 GIT binary patch literal 18520 zcmeHPe{3Arah|)QWa>u?Mxte!7S2mrs%ckZDMk%MwW;>_OO!=P40*O>J1KcQuEeX3 zcjVq)M9D71C`PNMC@RJdEWk$0q)H*FDIlaqt3$(<Nex4Pw1rT#u7Vf^X*vnhw1r(+ zjp$fWXLe`qM$6lv0s2>aPuQFHzW2SEdGluXcK052x~sQ4914My5c~y{T7m)`=_u7r zw`xKyY=k?{{ne#A5ttr^ss0d5{eywW&2_N65#SusUK$F+@(jT15yZoI5Qp$w7^a6B zVVdgU=gk*aBYzbhXq(2JdlOLSL0JA8$_6|-QNOEW|5QKryW`MS|InFm+s$?6@}1|t zeQ_=__!f-?Fx#m9uo3yEJI~F!{-ND3-W&*B`XB<AZ*7F-`;qr&<ikO8nS4lmH9S2Z zsl9w=t>>TkOa0>WOxRo&oUoe%u}il$lI_2_h&pP?UKsVZqkngv`|C^QOw}~S2D$x% zQ?NW(9V!f-MOlY(Gag2$K(_IqIpdgbT?8{sb8~fh{{N}#zw7(wBh$B@4PV-X{I}5e zx7x$gKTbw2-TtG<^z!klOFzl2y0rA@>al<QmHWn6?@JWV`PYE#oO>M1JJeo-lG+Q0 zVR`;pJUSxN^T)uAgUf%#<1g&RzCne*426XOuTAT<8ILnKzl8`qz7^+a&Q(o+KMBhh z)=%{(@d*F6yH+m^UHx+Z)FT&dT7znMG&&XWVm@bgx0&nVSIJil?B$=Jp7~eI!rd34 z@Gv}heBUoXeEwy#U_@ZQH=o96onb`(01%ICy1b135dI?ia6j5V_0_8BmocX(ZnT!v zSG5^zGYs*CMYFJ{7AEF4L%ezu#P?KV{UL~7s>S+xn3$<YPUL~hr1w^&>Tw#Yb%cI; zH$MNOiGCq>t$AuHLi`6GC%((wOL+pALz^x)?lKGQRq(OKU7mjrqYokUf&6TsoXx}v z-?CS?(Hz@D5Qh)FIECTCb@NGcc{md)xVi=?PF}2NEX7aqbrEe3pIJ5S<*ny~<fhKq zdGrhYn+^?`g$DE~Gz6%7>Wg{};Dft6-8mfQIXvr)Aq=^6zEO^rU8Cxo7?;<~0{JKF zlxU0<*5NuYtcIOK(O6*y<yJ^W6RlO#iTc=V6+9B9b9Wi@@{zOV_IX_Imd&TPpI#d( zG|V+dkA`Ejr_aE066@`Foc;nVpRNxTYSuPIe^A{NJsk}dPB$XAIu(5r+ewt|cr?^m z(Ig)2cr=*9(N*<ZqDhns--X$Bl;8US%r360-@aJ4CHe*)i$8+dcNbxn=C+8rw}3e_ z^qq#^q&0l!n7N#6UDZZ?6hm4MqsA-%#?YvNf*Bi%(wwQE@_!!JqXE}1_wB0b1@HV} ze50EmlmlP+A;v1=wcnvJgB)+Q&YgGfJ`k&hoqMWaVgdR7oO}ZN_ZTo?RzZ9X=HQ+! zFfnx>$|jgdEZvPSKJc0C@7^?LhcJf2t7Ef?wRqqfK+_}9_NJ}T@H)(crY+G3o`aMR zL*WqihYG{1L$k?mz;a@3Xm<FwLWLHxQwI}3x;Mkb=f1bnmq(Ga7^%PfPUIns-M#0I zfqnViU2TGYX%)CRR*$$~a-Q8^2CJd*pD2yL74gQeMZ7r24LHY5I6urO%DKQfZU|vN z&T$jY@iNY_9_RQ>sPN;T-hE)WeHC86?)CkB#KpJ&Q1u^S9oPGw?-#mWHehZvR`qW; z&YQF07hpTAhgtdlk^Y97$n=>i_q(MQb-?~u?}6As0Ncu0PFK!JjU}8^HUq~K>9Irx zplcxRQFa@LWBmvB9o)Oy*zfik<F+-DN)p?!6OLu1vnPzEt?B$@Yf-NnH{eijHt!hO zqsDMHpBc$*GhBO4Dszm;SSIp`k$t)D^ht!MZD)t`IVV1nO;D@YK4E)J$T`{ZL2(i> zRG&^+_EGMJ^yuLfy6^E+XDZX3P8}O{gqI`djt~#!(=4B1*>}Xl`<`a`j3+x=Sngoi z3ZG5bs0B!(7FVJcSE3eAQU~_;Q3p!Y;>jH>TTxCBNRmL31d{x?CvE4+@ey>@YhhfR zK3oQp-Kk6>O|ZFe>V-W|uKE4%eDL=49^qAFB?6TQR3cD`KqUf|2vj0ai9jU+l?YTK zP>Db#0+k3<B2bAyB?6TQR3h;IB?3#4|Jh7`Uf$;d)Z+X1vgN+ADB#Z><x2(k;_`nr z4tvWlJN&%(RDhnK{KVhU%a*CKC_s>&rT~6*03O5-!h`&Qy&WC9ji$W^pETmxY&tob zNM($pS=(?%EhDyl+|C|NrLkrwM^lcKbn>=kv^BSGZ*AGp*1V(DXiC^)+p*U2*kgn@ z?=YxmM@uX13iug?&g&|8|86--r0fnBfC&C8S0bpXT!{egNbwc-$Gb8({V)h+?AE*J zeXt8RhESQ?;K@&*2qS-pFHp4kMM?x#W`$=r2w&-c43&k{yd)3$8J9L~JfSj-2l3Cl zEdc4KU$zLJVVvEC9OD-mkF)$8#&M8a)-(Pk#%p}|*BIZ-xXh%$xZ%V9p7AEe#n10E z-oiNUO>xUdjQ29m0@h%K=5@e_*D`+4hesLjV_fF-7~?}e{Ns$L8JBsHQ;{;?GT!>G zyt;O}dP=yg*C6B4zQA@o{Sp;wdBxMe5+8N-l<+3zpJH6vBEP_RAM*sKW(4?0W$q*4 z*<FdBclDI;89qN~Oay;G_ZLskO8k#qJte$H4UE7qs+L#v^sL1H+|^UUC9X6o0yQi2 zyovk`lH}Mc{C`1wB^%&B1Mn)GcR9WhfVUz}cEz5|{0YWq*wZx2X9DzO0`NTRk@HmI z`FjEUR|D`r3Bdm{0ROuHd@%t3uK@hR0K672{pI4kH30u)0NxjXI|2A)0RFoH_#Xz~ zmjm#t0r(pM_&*2WKMcVCJpg|{0I$XiUAZ_n2H?2QsVx7~0r>L)_-g_9)d2jv0r-aj z_(uGGE;p~10DK?fbe_J)U)ge=eui=R3Xt!q=NUKnQtw@-0A2~u50<xQC~Na>oaQ8K z8G$X6kj)L8%rO{G<c{MupycuP{L!P9&AW>T1v{T{d#$m=_-NL)0C%?}4&)tclDWk; zq;mT*DF+-J#ygd=w!66q63JvNnaq#n(+MYQ!?BZgR=4l%?!YZbj-TU!xf7N(e#qNO z)SXH@7VD?|O#}IH%l>RCm$f^x8FbINch8dAu*6l|t3;0U;@F%+E^_Te!p`6>r}lI< zc|4vPvsOfk;=z+oVnjMIAW+(D<$8)SJWBh0Ql~6w=iPll(i$90XOBtvfm_9WP=kZx z2|F=X>@O~&x3!BLa6>)$sl1i9_F5UsP9-~Ri#8tJgAG`j5ttm1#q%ic>e0fak}yfS zJeZL(w&D~ZAI^4)s^f{{7K~YA$?=nZs_QDx&0Dp8+ResU)`1~(8M%`=#~M4FNIB?< z?Rc*3wVZe=dE8t6!M(kQ+GD+ghq}85y5fWJSbJ~RAl$q7uBv$JfYKft8R@gLNh_B- zm`&xZl6#%j1jSELz0F&PQ_g5SdsN}><}F-IhDy1%FXv`BjYwtM-OY1wpfwK3Y$lgY zTYY&4A9ZZ7#_d$b(HgrZF?+oXaW#Ou;yB%>6863kuQgyf`|woA6*IfI1JB!8N1>zb zWw^@^2GD4{^?)xLPhkqW+tKa~l9%aTP)n*xlkdysQfiwa*(r5CojB2D+jtt68#zE{ zXe@IqZRJ#dzq?zoq@pvGa}t@Pg!5kgXuNz!Y#2j|SDqfr-62>q?^hr1JQP#bOLn_) z4`kVnpXrdR&X@k>P6=GRF7Ik<jo>6odA8r(kg2=-v$(8y2Ie|4PCuTtz1d?uiOfhE zuNz*eW4RIU2l1<>Smb-)A;fv>q1$ILgPuP$e<$O_=PimZvWxNieSA~#Wh_B*e@FgA znM0zN>w?SkYoEgLtEpJx3ddWp;&UzS!K6a|X#GPjTEa#Dh{CmgN8wukB;ynZ{mS4R z;}Yi?ZokBG6URsJtBebuoA6Dp_~ZEo<78K2PS8Ipyp8K5mK3hn>)#mnuWvQ#rBaVl z^X0zW?<YOCQt|s~GERQ}nn!Uz>A8}MtgqL?d{BDydc_$he|}xaD4hU3lL30@xsM9@ z^GUDje!i;k-%$7r<K$=QX%XO}53lAiUuT@+srgqFpYlrhulx9dU-j|pSpVNLPX22@ zuPc6|^8bdy$*#eD?=tS!v!wWX6Y&QD{M(98`j4>wj})%28~D=6E&e>A=S?c)kLlLD zkDZMB^Ha`O;_LkHRC;uLMim}Y`ll4$uJ9Ka_xnlDn^eedhgWq!Zz#M|;qwaD{3?8Y zp+b7PysG=To^i6<sBlB^yA{4o@pYVg6koqXKBD+~y@nWXL%Tgn|A^AFPvN6VkG4zC zp;Y|qa#rC_cog^ZRfX&8%mt-i$AO+Vsrd8Zn@W$)hieMo?G1H5uPgl&2RZL<_;5Mz z-d1|(kHMt8t8n?wqP``C>pZ0AQ!4(vs$rbs7V{|X=Nk$?pzwKxA5{2~(y!z8k;1v^ zjiSk8A-jjXs{2`|aQV)qjx7rRl;ZDHIKAVQVlqzirK-UlJ&gPFtyk&M`Ic7rfG9_K zTj6pKK;5<c+)ML%Qt`Jb{3(T-3O}syxWeVyM%`(JyMOq>W3DUQ{X-DO-&XjujFDJU z_@@;v&+YO(JHve+FyDXwAkXvu@6#%No~QUnm4127_w%;|@LL$C?_YgiAu8!lc!#8c zQqCvBbsjb`$Iow3IPrxix##E0T8Mt(X}gpfa{d}hKjH6jTkMb?Ixpls{VpFLu%C+Q ze&V}(Y*ReXaa-&YPWt8kN&88Bx&IsGal)7Ts&R!A|2(&+6z<N8{W+^};=jsm87KM; z=Fj-}(!Qc_(%;1Vs|qLm7r1>*;lyuY{&j^D|01{N6;AwJ%wJMC@xRXP+X^SX$$VJ{ ziNE+Q@ss)XFu#ta@Wr0YPxyVzlX(bV^oo7qA7Q@O5x&ez`h`Ele38PJ_PFws<~z#m zNrh8<&T?C%=$G;5eEciio>4gI7rhr1PWo?f`>Mi;KgI1ig%cmb^Z{^P;lvmJM4!yJ ziTO)DzWDu~!b$(@q?`(mllh)!UbVuBFZo)haPmjyZz!Dj@_f~zaN<i`<UUjUpTj;X zJwCp~xliGZ$m?_2cx_ZT>6bXleJSZDzLZHH{~FJCO5wzB;sNIrPWmMd)!Z*}yT)z9 zhu`3~=p#N|54W-1T|WLixBdF-7&lmoUEyi{6#s4Pw_pER9&ai=`uZ$!75(R#cf`k+ z-&aQ!?yfJl#}!Wc<#*R9h3j}ibMEArlNd(n*q$7fnr)>M&F&lGW_o!I&BM7IG}~Ef z5Pe7Uu3|HpbFh(2j(Hp!>C#XKa;S;#ahttYQ3@!&$@MtyyS*YSnH?Lm@V(yuMlnzc zEj{0E6jhpB+sXF>(orK7mJgw%c$(Z6G0uPA+Q$#aAHxo^Bl#iu^Gl5LZL|yr$7feM zI8CJq+ptDD{o^Nj{J3v`*cS!lCQ<aeFzS=>*8|22Y$BKH8}QJjXN}kL$4l&sq<eiD z@Av-*kH1~3wU**1DBXLO8{bDK9hON?6hFnT0Cdk>ZvE!?CC)h}()!U@887RXLadzq zYixgp&wEx=953w=tdz6g$1i_s=%mC#_9>P8_D>;J&i-fvc3|o8MDbI`3y{Z3Ir~E~ zk1@nVvcDb=887q4|0ATV{VQx=;>T)=<E4ETE9LCZvHka$NcL&hfZzTrh=uTI!9y3b z(QD~v5JHGcMN8ijx&1RdzK-*d@_Pp!e*4tz&s|b*^_S@r;2XStUaMqR+BC0n<FB-P Mj0-|!DSiw5-v9tf_W%F@ literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/exptest.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/exptest.o new file mode 100644 index 0000000000000000000000000000000000000000..93189f286f562a345223a6e124c1cfe81e2be95a GIT binary patch literal 1712 zcmbVM&2G~`5T3;R|8oPu!H7z<5?RHTklJ!FDy19{hf*XY4w2(*l?W#e_7=Ilw2#1% zN8k;(aNsErj{!GsFk{a&+qH#6SF&d2oA28huV;O@`Qll((*ao>_yUVaP=L9&@T1C& z;3`}JAC9)ad4uo6WV4*_=)y4V>z@VxRNmIc#=5_}_42j9lVxc#jwdsJH_Lr9*8Y>; zJkNF~DSCM_o*12&y<GciD(r>*U`+*~zZ~b&9(w(i6~a~EQzqz#kN({az55yX)!Mz+ zdNKeWbXzy|FypSv70^84YlwHP{V!NT4?A+#?Fwk(1bcASr9;hc;`fo+vG}W&(u4C> zRJ-*)O`NhGTx{^~B68E(=lH#JIX5^iDuJaEIN08s!O{pu`Q(Gn2Mi8II(Y}8qfxc1 z_qihBZC`=#6J4ode`?|(sKVs69gAmlX+Vu)6N4HS1*klufS7?=#Zaell_n39D$SBO z6&$;KS~adtG_I0tI@L3|7mWk@Pv8#nX?o5%x`<;rCrRHBhwVMIq<1Itxx<r?xb}L0 z0o6FI{vm2<&k!GbN&QPUh`zj!^bsM}*8dyU+4D<~=s69K(V<%t3BdL<50A_f^+C5q z^tYHtb=vBG<h<}XJl0G63Z1t4Ke)csq53rEvY+7Z5u^IjC%V=8#P%&)F>-FUZM!GG pS#ZQe`cGZQ$E{Cy$^G^uEuHftjF!}`Bl;J#>wmKTK!|Kz{a*vvZ*l+t literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/exptestBolt.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/exptestBolt.o new file mode 100644 index 0000000000000000000000000000000000000000..944a009b7cd0bee73e4da017389e4fac0c625cbb GIT binary patch literal 1720 zcmbVM&1w`u5U$<vC;p-FB#6*Lzy#c8XF%BKWi-Zk5Dzhe;9;4a?XZipJ7K0*#*5|= za`Z90dGX*=c=i>%<r1`NrYhUc41#G`s_N_StE%p)-cQ>vo^?ANkkx^&u#5x+D7>W~ zmTm~w;3_CM-2Ltie~jWMX=3+GZY$omlO_L5-p<z6L$$v1^0nGa(<Gim)4AGDGi4`6 zJ?<T3>Hai9FN-HrYht^|jM~&eFX;Q5+7Hxvl+AkR^*1&M*S?}1zaKpKcQ<tQbMWhT z8_R3G82}HuZFIz)OJm0M(l&4SCgNQu|B92*!;b3fP6;$|f;~82r$fbW;`fl*argsA z>A^)Os@y716Q^AdE;aZHkyR(p>A6gCU~yV#YIF>11u(F?n8Vr_#@Y0}$%YJ$kTo2e z_#KFzM%L}3&y@*p`x=D*)t$~i%xp9Qo!hLk6Y;DmEa-7$BhaHf2c4x95YyKK3{4W1 z+vMS<PSQ9^1jjC)md)!%^EysvGc)HW(zvVt0d6CirszUV6ml&0B-=N{VS5)X>FX2v zyvCD|xbC94p&Dn^-$yOw4DjbJsei=<(U<c`A0c9G{l8(IJI4fxp10u<I`n!%0oZ=w z;gNZ|j5xg-(cfYo)oH7L#QVbM@Ki7HD|FiG|K$2ohw9UuOFqFDh*5p%6WwxsX8V?{ x7`Zpsw!M>M7928>z61Sd)$7w+s(*Wu7MyfIfwQEpK&$Aq>5p0eQHX5o`aj^Nbrb*q literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/exptestRR.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/exptestRR.o new file mode 100644 index 0000000000000000000000000000000000000000..b02c228187f2ef3ef0be96992af168443b1eee34 GIT binary patch literal 1720 zcmbtTL2J}d5T4yst+hpa6N>PJf-Sg@O+ab&5~;Nw#KT%a@UUdFuk2!Wvm~z)L9jo; zqd&u&7Z3gl&;A8(J*hL<ncZg+Jk$qaX1@8pnaRuK!{M_h?N$rqwBQRYBS8TQZ|R4n z8^Q*xgMzc(H?RMF5FZw^W0Tunugre^wd7yOJ32UcpmvU)zf{L*n#7}MJXI%YrtHY5 zN1a)go{SUpvUoJMCbp-UQTsaR1YLh$`+?etvPlQM?(Qz(+E<kEyTQGGPebp%0zZE@ zvAo8c0q~&RL`U4YG-hm+wtmAm5N|v6SDlI;PE<X&N}!Gt?7^if9p?Nxeg~N?hrj12 zJ-FgTb9Y{+j#Jiyt2MqtWYej$crR1TY`HEvhV23tVefPb+d~*;<F_X3FW~;r#BZ>c z=xJr$DZ1R5@TRXp_+QiM{N2Px1JJq6=5{2WHH8H|jBEsYkmsPYlmcS<dJjXBL}i*h zOzI?!qeO6=^Km)6t_-i^bTTnh%ai_}*+MyO(d9~+kYl+gNz;D0=QakUuWsm5m*n`w zbr0<g^|+}1E^4V}fRB5m|GEpJFYhCBgoriG|B7|)9up*bPQycV=<f*yVEdVuNA_tA zar$dSf0KFCr>Xx(&I_Nzg<j$p=rr~J!TqHV^`||TdV=SOQGb~e-ST{5`<ks7xi{A~ t{U_%vIAh{9jIZNU?N9$w_1lxQ;G*{_aE|m9XcL_#{W<I33z2PA{|AD}a_Im7 literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/filter.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/filter.o new file mode 100644 index 0000000000000000000000000000000000000000..9a29d97d2388558e9058e4456155b6ac8cad2c61 GIT binary patch literal 1728 zcmbW1&r1|>6u{r?_+xgp*v!MG^4;%f<g7K*?n0yzH0zckNtoIxA;)dDUD{vHj-V*G zf(NgG$Dm^t9XbdhxFF%7V-WQ>Sf|2E5>oHG`yCvH_2PH=^4|NrpF8uIwfhsJK0yHI z2=Eb3Er$YBnof1Srt07a3GRWuE6#?d?*c3UtxU-Wue(rxA%CfK%|X)xSd}hAQ0NwV z#=c_SE~S;Weevn{FcrVC3n7^pf7hpE|F(6qviJ5xgqOY0Pk!DM^KC(m9JRsmkqGY& z`+a#mL<zRun!|Yd<Bb*2De+@0)GlmEXww8G<Ng66MHC_rT_=(n2+N9$c7*g^K^9U- zQt2i09Z;RWD5!=Hs;nj`lmy-f!jZ@T_D<&4Mua~K#%Effdeo*LANG&rPgV}L-Ltd# zD*!u#6ng^9V4Y5{U+B?QA^4%ASsGFMaL%TXUTx76YN8^9*Ed?j{ri;sqJ2buMTxNK zQ%9sI`6LP9iqsrtwS@MB>I>>sS-}{bTfpZfZ1_~x3&xVkVXBNhd`xGG#at?5WD7K1 zw5XjiX+kYo#dJ1@nw83AZ8K#rS|%OR;%Yn^8`5HNsu)&YMJ*bMFs{WY^TeX@TUh;! z!*-(ye*bIa78`C3fQY|FN5o3r6R3ek8_4Q3d&A)Zk`7njK^_t2T<7)<mvNLquDiwU zGx#0kwfcOdPM$Q%IptjE{1NAKocC}J_$qAE(o%4B39?yhVsf+wrn80TITLcFbi6ce z+Q~(`m`;yc<^tG8Aq}ZwIbC;-7qWI;OO#5v<+?g$mQB0Xp~U-iV_(116Xm9h*Pm@2 z9Gt=1`P^M7B_6}Xl8d*yIB4bNylu>*w5__#IGSbV49zx|Y|x$=wgK9FxeQvWn9rMq z`qb`1=hG>svC&#Q={mPp`P`1%`|i8Z!M0F$0=WFlS9XcptUfE{Jd+UT*EsiX_@1XP z53kj5bS7`$Wi`*6AH!VMDvH;Aoc>ST5OrrPxAb{pm>J@5k_WaTW7qrt*{*qKM+6xT ZXPMzTPG1LILZwl@&OZ&qP9T@w{QtYRz5f6J literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/flowdeck_v1v2.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/flowdeck_v1v2.o new file mode 100644 index 0000000000000000000000000000000000000000..6012d21e811d8d93803f5d6f8eefe107f06e9adc GIT binary patch literal 8096 zcmd6sYitzP6@bs~7~%$!@-V~@YL632>=ZWM1yo!`%@}O+3|Ph$G_=|s?+$pyzL=dg zc1fB=L8>G1!zlSdsx~3%1B{XisjW&{XiOBTRG|`zRMe>bVWj+Ut3;(GRdHMDo-=dK z`g(RpZPixlMZ>-4yXSS!%$>cveztp8PdF3;X(9L#%t}H5^p&$?!yOv19G1b|W8WXY ztHG(;dqd-YIuIUT1~9f9uRkZX@dvP<K3q3Gt%XlbJu)x*yT|5dKm6=HSu}r<uDbGx zz7vsgTRZxE-@`l3+HViN-1pkA&)O&9k)~H)da3XDn`iCAINpKR9SzR6VQ+-W?~(0m zVPpCSco|@H+|(M*6MNxaW8~}eCq`~-OLrDO4@)PtrH>MCJ{dalVIB1UMO(S^sV9i9 ztnjtSC&ETYxehjrE;pX3f4}9c^=%897qzrCeH!OlJN2gDhT-x=7*0W*(E)#(+4w5P z)iG}KMEJ<@zs~eij7DgD_df06m)}^iwuxjj{7{pjJ=Ams%6*jkq_*Px)VG$byZIcv z`OzzI`Q~$r*OA_}nVAQ!pl`h%eb>Qay&gJ#hHMg9eVuW63S-|yxmnkKNf+9T-97e} zTXVo1@MdiwhSw?b2aU$`-D6kI-NKj<ZoYx{lIF%*+<9Z#)xn%dXF`kLxO?oU-u+tu z(@RmWh;bA58yyLNjfo{#7k~}77m&}lU48O}mmBLQ#enjAEe%wUCvJFi6a(|ZT$)#b zt^a+dU(I12>ZkD1@CwJued0^UoD%m#hZ>94`+t?+lIr|u&Hv5&f&L7-x@|je>qiIE z8B0&+(oWjUq`#8R9nzgaOYePh-};XBs9v;k#k_ql>cc?tsXjAz$g)Ym*0XERKI$tx zMiM~EN*<<uAlZ}2AC*1^MJHc~%OuWc^G-USL;ZBo9LQK;rp$tq9<s=m+CjA5>!f<p z!&Zu9*ItZJPFWep+|T_NaelDmIGA159PTqQZZ@5Bd;G6h!Z$*`<Ydy8y(M4DIj+AW zB{Sptb=||IPZF(e;c7I8Tym>32f4yOv-4XV_XC#k*{<2<)uaGHJSd+a|Nm=#PeA_V z03KAI!2tar{_py)5AYwv*97PX#f7a~wtP-+-Mae=dVfBjNe-InoPH3uChfz{bp<<r zkhW;2og7R%R?;cimfjJGt&6osJ0j7T-fG&}bvSBoYa<?s>NFE=k8KP{gfZRUI{3p( zEiJ9)Cp3VD|7tZ2J^9;W7gRq*4amca|3O7XtMT-<xPGdi>ecM0!1lea9ss?D$o~ZM zZ!kBQCwL<W-_2Z>CVsrQ)$9Ed>W4%b$Fg#Iix3xCde4tYsKo6E_MwV4jlEW8F0%CW zp-B3&kA;7exnwH*JIp1raKxD9eCp=37FVj~-$lcaqQ8l)E-@EbdYaatdUtsKtGTCN z{Sx)`tGTDYkh(d|)34@lpjHTGxsG{D)8Kv?R(j7*HU9}}gcSWm#e&wmNRhmu=ck(g z9H&Ey{;*=H!4gIChVNrn?FHcX0h~5;E&cm&-L-gQ0AGWAG5m2x?wC|?Lx6ry0N)Y7 z4+L=9&$aS=Hh_OEfWHvHUqQYYW}hor-w$0b5>%excU@jrk!3&qhPl*5xO;G+b549H zIuwf}VfAnY^_#`RusT(dqy1LVnU%KVF{~oR=1Q(+5zj+(sG4&&Diy6xK0D!g2~Z@R zF7H^CntSd^7s+cBygml;cqV_S80TYEJYFzuGh6hIX%$Ikx9-}rxpP;1PfyR@?*4dx z=jL7AaVU-y9V@%fOgnoW({?C)vOk^0b(z@$4AF|atc*DVUEN!D#<%uv-xJ@yXFViK zwr%B{C%r>pA$ydLn|+p<Vqy*y0ez&irjxh3b4N;6$#RdDJ?UJk%f@q}y?JD}nYAF9 z$0KUS>Mc3=(P@KKu+ur`Ah1ifh{Ke{7TYo%^x@jZse*KqV%}PPG|IGqhtJGNykJ{H z>3pdODHjaS0%fl)#pj_FWoh&|M~!&p*+6-fOFb^{Y(n%Ui`s*z-{uY7|K+_({85Fw zhgjDCjKbx8(t-MG75+4jiPINDX`?(K{}F-MpHcW@3cnb@-(kKS{iy5xfcdA8tLvR& zzRaipF>`;Ob*M+pUx$VO{<y;1JyZApF6REY`xUO{nPBeEU(OwJf5ql$)|Wa6Kf#>z z>Fg^xjWVZvRDO~<tv9OVe}=jEk*RMhTzwADF&F=$|2lK3Gk<k+r!Fw3xa&n3`)kZ) zy)t#3xxb#b6n%AFA1nGQzr)<W-i3VNp}6Y07BTlf=Z(zCkL)SRb+zJ$;u-|8wJMy4 zE?>)n)Xi`y+9_Ps?_z=Csz>h(bAR0miXU~qj4Aq*=QfV}qN1<z)6D&KdtLFP*6jjw zf88!Be$=|Xqxezlc2(g#bThrig1>H)3Rm?%V8LHEd09x^q(%#QL&^RU-oTvn)%r9t zmwcq2tC;)i*6#De<%bOlSL?aS=U?<6XYSu$26Kw5?yq__q@PMD|3Q`|7I7+7g6k#k z58+ZTgYCpmf@SGNe**nclQ_cVz2?p0Srzs0_g0Y4AwL({pMRMrbnYb|;p)27&m)N= z`V(w#a8I1{<r(T#IMwYc%lj2h`tqEp>m~i`tXJ^q%L%cpaMJ%3%cBY>|Me`NRygTT zvV4Yn$^R29Ur;#dPqBPa;pCs@s9p6s_r4Ij#j>n}{L@;cK9f8z^~5h9Zj(5Yk9_mH z<I}HaeX%2beuQ1kMLaM5Wj#_4;rrRI?(?5uxmDqmzr@(2a9Zym%Z9>9U+!<O!b!it zvOk|PbDew1bChL&K2ipMK4YwJD1IatLjHWtu%6UI>M1s|KFQ|->qDeCl6A}h>>b<d z2W4dA2|MCg!wy7Jrei{6pjd>6ohO0RqmfN0l9Eesgp-j>K8e48GRL#9cdU-c(U=dx zf%ANH_U7?xM1;R5c)<N85pjR-Re|Uv^Vuw(|7C6eL9e4N-5Ys+#g)N>UU`sMUL*?K zKZrfm-e6g}N&X378#~6oUAS@NIcj9ZHOzfsV2pw2i(k3VBGVb2bo}<G8Tj+{+tb;Q z)~}x7Pz14GC=V_{Y?6=QZe%p}$3Mq`3S^`-u@_|EpjQ1_@eg&>#=H)wepE`am->Af zS*`eu{F9&Pvzv;&$h41Y#lOh$B@V?WU*b>rGstSi*Z;-%!vXQH*N9J_DgOB0?|0Sp zZ{_&9+$glACib3$_ZbJZ)<4DZ<(y3Gr{5~XUe^CTWVO~W&wT>t)h71B#&J+9{vG_| zEH(B1)0Pr@iT@U|TJg{EzN7l8P3(pJ7zefDk8*$sR;2aQUJ`qW{|jUkza1~N>HL9v zK!rG#+oAUIS*xm+*}lN{u>mJr@$$!~bAW&Ek)K=q!_r3*h#)qfh`(jkw%@kGRR{W` JsoMPZ{{SPB0>c0R literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/gtgps.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/gtgps.o new file mode 100644 index 0000000000000000000000000000000000000000..f80236e5061f3295c45971c003b503f665d8e5e0 GIT binary patch literal 6920 zcmbW6YfK#16@bsotP4(@);#<mq%dG?W5?buw3Z-h>sj87NkU<(x^=64^N<%7W|tHT zT5k|iiJTv7oVJ#1DcFrv!!O58)L2a$V!2T(|FL2x>W@}}P(?)Tk0i!TN$k>dX3mA{ zVMkSRqv721-E+@5_sqRBv(Cxp_7+u9Kr{t@2kV-k0F&F-`-asupb!eEHw9qS&uPJT z%XRIYd!xUfxu-!^17qcOmojr(gV|+GoeiN)`6U>d2MCZ|)C1Y53M(<>FCu?tbu|z| zcGv?$A>@Vvfy4PQq-=sfgOce~AoDiHdLg62mD^qZnR}yux=1mX_G<l`{{dekn*~kD z-YJ5WBFJ=-?H!DbYniG5$X4R~`CY~ead-f}QQ;4j!Bnh_^oSZMyNH)&gvtcZ-`rSk z*_MRL?i3j-OM4sp!HAS${6EO?<+x<Oh%qRx#dj%LS`+bwUr%+0zcp({RbyphOQus@ z8ohb`XBB4~0IuiVc)l~QXxdcs)l<6*vYnd>UN+xfR4!NCjh}A#@TWI>u|^eRzc{j| zAp3F4Sj$=cmZ!A*Wf*!3)Kf5)SNhi7=F?a2j$ikT?LIqkH+0hjo(Ct!HWg*YGDj*P zue1u(2j{Wwl*=OKM)g&Sjk?29-D!=)Lms0ZM!s4Ik3eC0yD~IUJn_Q`N6o2@3%E8~ zBk=n0KJQ=9nq~l$>&U*l86suBSzX<6Z}fF*KTuph-WO|6EJAi(E1JD?Or6<=_vaNA zvcIf^?0eew*~M~LNv^K`YP{CA!Ta8Mob-luy@&KpTPL4U(j)77kaW}5D{%Z6>J)E$ z9I~W;AN9p@TrclQ-0*=gu7mdFqNdC)U=Ed7pCH$V_UZ-I_SZ0F`=C6V(GQ?M+7EY* zHQ=7SX6;GxBQCLiS~sm%!I)I{IlLbV`klvkBG!341H|yCO}&Hhma$G3E|5*Jm6IQ1 z{q{0sUp1BN9*j*f-otefC!16uWOd{x)ouUuqpx?ZoQr3#qJ0J0l;GIaamDgS`Zm&^ zU)Kvz|Nraxqjf)NJw=#jNHyvW6%G|+U!1iJ?s1@Vc4@*ohs23(!ZS!`u?nSzms(<< zQyp``y;pCatE>0b@ZRVZE8eu4=@k3rRb1DCwry7Au>6LS{UoZ*?8G=b@LD<UnfdHd zuyV+J+kS3<ai&v;X_N92?0f{W2Kps-{wnr0yFZM%UfB-We`AbKwUSw?Gu4;u=HKww z3t2t|L%8-p1ntYKVaSj7R!9BtbIQ=<e^&!^)~h^F&;(E)`g28{n-2wTL*xVP-p4Z& z!~TnC{|xPwi!h{nAb>S`Tg5tQ0LA5#%13j!e=0$JT<ML~0qz;HqkI0DrtY6s;gpK& zQg9CCdQyYq%BQP=3#e1w0H4pqLjZ^7wTEZvJlJE~XXmlDG?w|#Dvp)RZpE=TF{e_D zO*wpkeH@3Xjwb>~Y7f;MsHr(r>+|ieX?f^@bzbW`K(MyahQj{qK8qjl+5hdY<w-d1 zrODV@1FaohkLk?=;Ygxyphq|3;TXwoGuf}VCX$hGB9I)^(Z~vC+ta*`)-Jy-TS@i| zrtmL7BAm8ma=?<kPjt0Yr`I2ik{n3c2Hkxlq(Um491M!dsK?^b<HRFTD>HjsK;*CI z(dZX%&$vwe(&yxEX}Iyv>p$a?k6Zq2F7|GIptZ5_F}=F=$?xfbWHJ%$4fhS`-APkV z_r`Vq!9g?G-Iu_g8SU*$$D`?CGp^TrYY*1?YU;f;wR&~f>_3P--@bjsy)`<G)c9%- zxg^3^LFs{yR&!ZtIlqJej}M;098E({&bHYC6y^T51yxn@Pr7ItY!clyX@7og<Rxf9 zezvmZR@LrQG1pmN=5e3kyo77azsdYV=Dp1AxEt5og5!!*2YioP?MdeNEVf!9%O9X5 zdx}r(VOxOhe`DR^IIc+b6ctP`&*%9%OFG?TU(LF~l7t2uce@>TBQL{1iez7RpC1u* z9ol|2ayzd5j9Rw_UhhUeh(-#2n2I(hIw&=ecZWS-$KA+BaafV;+wSx8Wl6KU&!P}} zM;@GV;b&a<ITwD}g}>>-|Kh@LA}_?1g?OvHz#HQ4F7_X|@K0R0iv9}V<5h7dV`xV$ z4|%To6tg|2ftlHDhsA{#fVEyv8s943C{&Gr)eXc`X{d_9VAxE>g9GuAG`_QXdcqx~ zo77LO^=ayN2Kv$v2@l7j{V^CGjD^#26ECS-3w^d#KSUrHOeA|!)|)IC#2DfJRM2{D zrP5|PnZWm$IS}n1gu&!bAlTaeRD-`g_*6?vS92g3@HezK2O*jqNF@{Tj^Q*uj7^9S zntcQ5ZWs=m=^85;dl})>aTp2U-$r~@Q$94_6(5K-h0|epnns%9iSP-C40rSF*0}95 z(g!iK@9DT1v|QQwaUF#y!g|V22hrc|;PhOeR*JmB?pl9ozfyDZX^R4ofB7Bx67y{i zeu+8xspLM1IqnnR#eEWgbKzUij+!%{Di`kI=eN_|VD79>6LZR6)QaLQx$po#+MRxm zGI#np=fdy0_z_7s?^ix2M{%ntL2g?lPWMHepRLTreG$Bvc|H2sEu5g-$(-u8N8-A~ z_evbU)2$}<gLv*&Oa7}RdmnR=kFYl+|NA8SHs;Pc3^J#<TtaJBTJkURjAUOW`F~F0 zR5ydirX0MD`8noPpZ&~8yd?2QC4Ncba@}5&xNLt-;<Eo6F8mgAx{n8>xc`#u4@!Jl z;_`j>@Fx=a@k;iONL=>sV@`FD{ntr+x8$cy@+12XNL=<mE%~XC{Jg?k>>q>2UX$!A zCHor=dvPCcx!8;ILI1Qz`(c`Wi9Jl59tq-m&&T6}v$`gTi*G!FPX8Tjsk0PukFqYu zrCYa!xi~k%KE&K$Nu2D(J6OaK_PuN;;t2aH=3-pf4>A{0*#C%mhNZ9{VSQ5Kl+RAq z&q$o=oMC;MrSLD-e@WtGFZ|{^xbUkx_%!RnpYYEZ>KyhL#eg?;qCXvufR{c1EZHl1 zCcdA&Y5D^3;%7w|ypdE2yk?RVGOzL0p-M&;!5$8J6Uk^eAvpd@Zn9qGUg=eC&%y5y zFa4mlHS1HvYki4$qsjjM_<;TUT%`F$rH&JEt4Lq&wkN|Du*~O#)wTU3^iu55eKiDN zd4@lk4W9oM<P=BTFR>5k9Yb7xR-+1a{1fAGQluv43q;QhV$S)KJik{MvUJX`K~C{& z9d=?qeTU0U%%?fjn(@k&zd@T6o7h*jw!VI$8`#NJzrPmQ7Hw=u^`j+;_@aJ4MwTo7 z2*(%p>}GAg(2rs#S9~4+VUn7NL-EO%@F(~QWVzyJIQ|@t%T3G|jCOIZ_;nn=g9}aZ z=~teZFXI0kS+4j78@A!N+{Apr#<7zt{v<!NLu^R#>Dephi}<IJQG6d>a+_qsV=}}( zFXui<?-OTR;`td$4%=3|D)4f~-;B(;_YpzwL-ZG5p9pBHYjIh%{!dh{`AfWh`h6-l HhdcNmaHV~n literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/health.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/health.o new file mode 100644 index 0000000000000000000000000000000000000000..05f25bbb5fdb1c4ce84bec5c2e30ac9c2746e803 GIT binary patch literal 10488 zcmeHNU2GiH6+W};IL3s=aZF-Dx*q=|S%-LWLaN$nRK`E~LD*o$o75p7?_|A>t*pKF z?uI6WDx1_$C{(gV+U9|ZgcKU1K12ewaTQB`pva&|MT8<AD%DVskf>-VAVMK^zcX|1 z`ef{R>kCqDG<)y;?svX>?zv}X=dN>XTif=4VUR8c{gLK+8YQ|~GuO79rbQ*Rl)0l- zL}Mmdji-q=2hhKpsIi-9Vk+4Ej#XeaP620LoN~Lm3#hSLjX`FV$eO5FO~W&bpIgQJ zYe)Yyel192U+fEv--_`w0c+y3PGkJDAiZQPrOkI2fLlP(yNhV}w1IjF4Vx=am(Z|P zg1VfBr&gjaqhVT0(a$=Y#=qFtJbvxyYv)+M44S_R(AZQJ=6%{2u3bh^DxhU2fK@=- zpj@eC(!@+DMJuLhILGy<F`Qe4`q`z!PhOjiS~b>0H#lrpf%z}h6EK?iaCUZO0rW=@ zk66H(45DqLoinY8Dywj8ZEnffhe2BJ*kNw-@S2OULTl3Ey4aeWLjB}T6g3KH=}gdg z={d|%W0|1}Gx%3(wJsv2A7iXyBy5I`&(20^@3~zgMKvMlE#-NFv@T>~o=VIUfZa%W zb*QGH#<4eGkA3;rB%`7^T$#6TE~*MGQuYSh!?tp&bnGnbo69Rh)KKNv2bBG`vOq;V zT$Q(v7gdKwrm8}OYX#P8;0i#e68=mDtgmw6SSVgz6*}8c9kQ86bkaf|@V=Z5(1dqy zPGTPj<IfdSBXdo(naAxj0c#?6g6eXC0Ip!&PY~}MV&vW9<?tZ`omiDMfp{&euquY_ zDw-Jo*KE}Oxm9OioPDiSKAP~W66>r~{>3ooG4OfbA<PlOUd~|O*p6+g5#uVv$vkX2 z`xoOH`)8qMKQFJ%O<XQs{*+y6O_rFIp^?QDoq{jD&@!OS`6GRXO_|Qi%iujzNSlup zB7c!{$6ll1*UM4Afn2<uqM1Tk#xdf!Jp&(EN9T5a-Mx?Rihc6CbnJ1fj`zZ7s0`Jc zRU!L6n&dTJ!hOT{DX&NG8?URGtZP%)GhPG7JyvBj&ZziD;Jdalt(dddY||ucj)DI< zcx=z>jg``5E&6{4&KR$43j6muYa!>F5eL3UV$d-V(<bB`=Q-zTpol6eMV^~Ql_9<_ zY;ap2wVo*ux&9d9@xpY~Q`Kx=UK46=FhkFWX;R-etjG6FT<I;seG^087C`Sf=Ls}l zfL?V`!BYnIm5~2Gb+pzXFU*kLK$9l?svzUzf|5BMzW+G?n>l}Q@xE|g6+&yI7+PpQ zhWoo2Imof%y|Th~=w~Ik*AZvCd~JyL@%e^zA>KpQIgY(jd06&!X3;q3#k0^|PPw<f zj0eY0ou#o~|AWT9I#@7%8^#*(to%=K`TG6Hi@?#$#hFJk7n`xpF4GLX8o;w{)C_f? zokaWi%~m7tE18#95gF@qH&Y|>Y3x`jefl1rYwZ7f82>WfGJXcRpL@|d^3}oC@vk%6 z#tCc4y+}uX|KHh_yhirb7>$K^9rOX+`Cjn0mk4|O4*Ex-k!xvceCLtOVaKk;XgvE# zZrA(473(W8HWOU6p1D>bd_hgvPp*R)3*a&YC%5E!&e6p*d<MS0g&g`N{AIf{xc8j< zY!O9YMvn14@_md$r<9<@oEgN(?bAuFErrM2`M{%-IgYdG+OKo%Ve8tnPo`*l?43EL zFn$*<er~LU{TXG$`_A#?z3#^M1n)KG!`9Ntm*MZ}Vwz;1i(#`EAeWunn%bf}x0p@w zxH*{W&m_#=WGa<5AGXu|_Fz0=cHOae%bMN|X7~YAwZ*R0oLze=3wHaOp6e~lHIYrd zjt%PC4d%nCWY#{AFf;anEj%<&=boNq!WnTWj=96p{x#d#Y$APxN6nr?>Hfh3W-?{> znAt=oYlfZKe&|@$n)|jl-P5+M^`Qt0X#2eWp1BG3nBlFC%^n!tfA2$*-;quYC6dWR z+MOXa=&aF^ekg*ef4s$9Q;&sgF#Gxs^yNDP2|IHro#;_OG4&<vWVVlJfaA2sPIt9$ zbV8{6dp-TG_D!Dg>-$~pcX`II?{~Ft_Kb^uhn>kdqeT1Ncy`(cTtM~n49CAHg4>ch zG?*pIWK%=kdNDA`WbJg8gTx%&$0n&Ri^h6;KfxpMM!6Az8xgn>fp13yj{CT&zc0PR z-xeJ2g$oux|NZ!QH(#*i7DS2s;u-eg`{922w4<eEiy7W=-)=LSN+siccK@K+i&v6t zU&3sv8%n2o`;%y;<9+?vL_CWxXR|S~scuvK#>U9TO=j3m57ePmUt7y~WTVL=8|ycH z&&NRp8>kED)7gbs!3BTWAPVB&LL~?#Z*gCcc$WDkNQ>ryw>ZdroZ%o9`tbem`F@r_ z!4UpykKK87Z*CgA_=7)(>y_~SGOqi&=5RBv^GoCW0>QXe()GOxFG9^l;}4?EeD;@% zuKB%(ag#w5%|C=T<24RChaXqC&PT2Dq{15%U*mj0V4a-`*Z%)T;cW`n^PW?9hll?M zh4YI(7ab372WkG@>c)RQ{%7zF!RJFbmp5=RuKT+Fi^5H{^%`fJAn7P`&n@n}^YOPa zYzTgb4g~NZxmm3woXXXikH7Ee%;7O%6r?4h=QjV1suVNpqT{+45aYV9L$U(6-aBo> z^#&jO2R?X<55C(6@AttE``{;h@L%}gV?MY#h(zL4bC_y+h|f)(Sv#BXyvaN7_4+;D zIRrRIf_@y&_PA#_8t5Nv!_h0zBY;jE$dZZc;ePkf6HPg10y`e(;}5y@UVQ*@)Wu<B zFumQz1G|T9GD;wS3W2R7u$NUHpziKu>Oe-HO1is;?6f_Q@4JVU&OSSt{83`pp+UzB z7gW6rb?<1qzqzTc`~L0QJGVu<qfO0i+qx;98qB1UiH<{Ae4V5zF@)o0wwE#q!0Ak9 zBHI*?x2Jj%G&HaykwvihWSS2KAM}{C%g*+voH%E2gz9nEl4(vPhNyj0lpc=SnS-r~ zq<uuDA1%lJ>1PBF==QB1T;F+|$C|@@oztu%pW<aah~nj!yD)v%!w)OmtFzgMztx9t z`SAHU&Bd!9b5NS+&v}J=<MWEbz44j$!Ar1CE?%87g?n{Y3;yk{sq<+HzQmvK!KZ!j zCF%js{?rQn5`oKa>2ig$pAuiK@J8V4g-*S~ZwG#dz_%*gyYFoZ_r|9~;okT>DD*c7 z{T?6vKEbaOeEe?c6t6${t<Wi6e@-df>(48K&+*B*=5#^eGR_x;j^s}%+#Am~74D7a z-xTik|DOtH|7D(BQ8@cA@e*~@vc8N@tHM_SkEk_qwNv5V__Qh98=tHX{<M$Is1N^w z;Ol1*`*Ts?9M2gBQC=0ejQ_OIm;6f#4`IDh|4oH^_vLMcd-vr7h0og;g>&4b{uP0< zKd0Gwl&b=l{(qxzj<e+JhqBjy{4KyKUjK^}?)AS+;4&Y=KDecDZ@#rE+?#JhKKO{h zRnzf%$_IZ{;4+_=s3VCt4@(rze#&^R7C6UKzh{Sqj>H=j?u}=c!ufuY&%Kz?m+R^g z`VxOs@OfVS{gD%ViC+@9)OlCo-aPzV=*u|hhr4%OOL#IAZ=RGWocVXU6z8)+@aqL` z3Ecff+8x{}aQByI7k^OTQm04YQYR^Jsq?79z4?$6e3|FJ6}Wuvo%g{n`ry+(_$7sV z{rSL$f5iv?#s@D_M>F0p>3^BRz4;LK!5b9L`7FO@w+ek3H~mcG|8l{u#ZYrGoll(6 z6yB%su)sNQbzk3qn$PDHE|&A@>M&pPIt0%1>i3~8fiqvPp-<q<Kc)1C1kQZ@ewh<E z^Uo>%69Q+x&e2l>XZ{7nKP_<PTdIFv;LO+WZ5IU2eEl9gEpX<)tMuO#IP+Uoe@5WU z|48va5;*hK>j7OAIP<S6K900b;eBC#o7>GlpY(neDWP%?f2ZPy1<v~V{jy%*tgnBM zumsNhu+lG5dU{^Jd}~nru;8=4E)A-ob#^MgC2-~|H}dCt&DZ`=By(gSYwt&$O}llU zZl!VRiewXqvlQvEvo=Nc<IiG|bc#Dn-xz7gcjK8XI`Q~`%VA3#IwR^YVG&2lId|rv zcxqrE!GALQzZ4THyjG62ESBnYsQX`!mFR}5`Ma3oWvRZdO#a^!C>`o2mRr!~dGtP( z^B~GvT#T#N9EO}Ss^*n@#{=Fz-{-99wLhioqiiIKo?k=!ox=0W?+_l-_PbSnFvdmO zvkeyu7q?4s$#Uf;x2O4fO!sx&j)8^Ne^uF^_bgc3X}t%0?9YA2Wys&h81dTg2DZ@t z4OP1KLu&oJe{8Gm_5K|MwxIt@UHh0@<v+E(271w0X#SaMmoch{JU^$Bw%7CXuNypn zJuX?gRHE*aAll63B5ThUJL4CW{j`cdhjSe+@BF+?-rQq>+^zgc^sJu9?dIoIU0R05 RLiR&7F5`qIs@fw*{{vD@JjVb4 literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/kalman_core.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/kalman_core.o new file mode 100644 index 0000000000000000000000000000000000000000..563d5e817e9c5422eb2458c1eb223714987d37dd GIT binary patch literal 6104 zcmeHLZ)_CD6@R;HoVDY)hfN$Bn%zD7Aa=x^Y?n%;Qp?)dfgplha1no`-tDc=@+o(| z%iXych{|CorKpX3h)9Spbt4)u$_FY{sx4(Jw~eBzr4q746{-CY(hs$od;n2Yh;ZHa zc4vI!wU<x**g?yi_j|wh=FOX#o%NmS-}{;@Nx+)~zlN&DQGm-Es(sV#n(!Pnz~V_~ zdQpMO#J2Lh1m*n;&9JD3wrUR!NYf7#xPjD5_)MaErQB#b3YgBsIWr1syJpuz)T##u z=2|u4kzImT?PtBxBeI`vs@eeYGxg?UDHPMBd)MZZNvSgNqUj_GwH3Qpeq_&Md<~rB z#JZ^UHcVS@OVidtz<A|(-B9kt$HOz>8mR1u!2O>uEe-ZgLPZDpa|!!!`1*b+WMB?2 zyLrea_600?1oOcB2zPmyLvo^unRl=3Pn^A0;4zXno?@GSitWp%*jlCK99E6D=P9;= zXFK(tG`rAjE+(!>&VvIz(~Bp6e|=7g|7G#yhwl1qG>qjn`{}bVi0d_ZNrno|>ETg% zx&`$+sQ*qjorO)f##oCpTTDk*TeWhl=|G*KnV{;>-saZuBjl0qL`z@PK4LmGbrDUj zYt`&_#8g$cv8HDGW|w=lR^U#o!Npp0Zt{l5rTAxX++K`VZcuez^W=Phoz*@0rDvxx zSNOBqCtG{mysy@y{S_fTtABD&fSs*DvcT-Pmsj|+b+E4VI1i8ZPA_aS7sHslh3g^V zUYq*&x&3oD-!I5`c7||ohjA||c%Eud(*C`x)ZF+KpU)KKm3n{;r$BylPJuxK+&$y; z*1&oQK_wo6x5Bu$K_;7b-T>Dq0kRIb#=`)EAtS6k_a8h1=o2P?<|obRAChkm+HAC) zor20KiuYt`(AzT~xqBvLM6`ayBIsL#&)ub^7br)1miH5$5&jPNmm=YNz<j*$vXV_; zT^}~X<A*qpwg}7`8{qMQ1~WQx@%89{YC0vX+c~vOd#lBC(tqrWj$L>yTKm;z{aEep z==Tqr&f)rQ&FBOt(PTOwzZlZjsS$0LYG{4vBdcMp4doA8RDI-JfApHRLBHD6tpB~S zSs(j0zIW<h&_CY3T`TS}owjW_c3oKONY&|WeK5PZr3JYmy|uns-!g#vO~yUi7}DR@ z*6ZpoR6RT;>8+QZi2|<KmhIp~8tS6-POvWaMdeVZR)^;y^-g~@tZvp$pKa3(tU1|- zF7!p|tk{@OKb;kP&R&Y>36OMqQo-|LXyFD)C$8EPCZEZU-=Z(R6O(wpBrq3M)a`E5 zc~^$njyg*N)zVay9X&}6%%rBG{Ba{V<@X?(XrVgq%)Z+Mvu7?S(K5bEY3&|1n~xVy zdh5s6ilm&7DoVb#a#xXWkRI=YnH_!d%nndKr}tzH?#<8eJuXcmZ>qLZa|mYReGM~f z@#K3_MQ?yvDUaMTa&HrNbv$`WspvJxn?l}A<dv(uQy{tH(wWdh$aw^_^q#`H>;Ne5 z`17q>-=YU~6CZff%4Drkfc(B5+m4SPCybh>pFnvqm2vffT+zczC6w8Hy;dPda@X-f zE?&rGGWm4L9zm1a7=GM3=IQCtbSZ6R4ly$@{jg6z;?oav|6(bZkMm@a^p7idtV`2- z&C}e$C%5=?uKpkQDpBSI@ylI1cYf1o-?i_%#$Ya&u}7@*s4<)?7^RVv(G$%Va>MBi z_6qh$x|Fg@V}+FQYOFij-P!eOtgG8-w+h)P_BuN{2#<9cWa;Yc{)T^`mAZs#4cuQ^ ziF%r{<`)%!g8$ZP3P$p`uebn>vbrg-ZWY+%BCBzN6{rp12jQ#pd>$i6LjFAC%?#%{ zm)jVwvXMEym*EXQ{Cf-!`EYMu+?yFu&>5G6x^c!B!@17o4;b#x=SK|p=W~(aJRdHv zGTcB(jmQ5b_9>r;i&pX9FudJ|ld8Zo46O=pzN_&+Aw?4S1H#r&pspH#_5O;o2|ak5 zW8Hruz~{nkB<}~{ivf5Y##<{+BjPkJA8)rz(E-{S9%2Q%%JSJ65NA&SPV;u-v#oyJ z3(qfxxScDcVm3s^Au<Gb`t5zWbTP&5iWT|^$fm5KYxZ3UD{;CKmJ#<7S-u;VF9p^) zvV2XT55vAQW|dNf(R6OKnhsr2%el}!wXF2uWfhO-t%8*;^6SI9MRwxEUdKxbbIBG{ zCBXL<PPP~y{(86DFQ!M`em-|>nB9`((lazPfK^Bpy_pJ@{&C97%A`-E4wNuQuu9fw z_b^x(NsQ2!vU6kkOzMz(_Zh6-n{XZI<ApcA@0$_lXM${e-#_oeJDKB4K72RBDL#E9 z@ixRdgc}@0d0W840=^J{KMBA$Vq9tzUyQRY0O#k=&(8$#&j;ZA9QfmW!ubAr{*B@O zdM*fj@$LPEz!&j*45#{w_y%@f{rPNUxSwwZ@G}AUctD(=1n@5h@IMIP-wMFL2*4ZI z<o)yA8h}4xo16H2&(ps78halRPIn@2y9He24=|k8SLI}s35IJvoO9@>8}ZgQm@mgU zuU){!_1!Mu6lWvTO#vr9n<fkhIPndp^ABShm$)1sVRoJm&m%A3#OJjr3pmB+?}hUM zPJABcvVaqx&u2=&DgO}DZwff^O{UKXIPq1c|3Scs&*yntz=_Yl7d{nm;*T(WLBJ`0 z-X5_Iug^F)U>&LPdUBtTfK&YQE(_O9z=^9eobFj_JpN@*g-!t{KF{A2aEgDO@gY_` zo-J8Pl%;|vM|iK0%2=^dYP<xoA-psomMj(_R>+Y;^sd<UWz{a0NFfjRR*SK}iDGsx zn@x?<pJxA)W?&SW3e7=mCR0Xy2EIQycN2D~E+z+<G#kCnI4wFh{4K^Ehu3?fivnz6 zIHNHX>&eE&-`7?&zP=pXiXDpS_n%|_WEUGBpJQFvq4{@nfJyHED<97N+48&droQ+6 zStXCNPf^b27Or!-9}VR1&%ez4`F-j4=lUDiS*!jt>pe!Ey}zmc6q1k2>z_c3#_z;O zY_}Qls0d=8&s&sih!xCE_Gx{cP3&2;zJ!l|e4_d1PJupQ2Q9@1A`qKT#UJz5_HSn! MC+&Jw|MUC*7wAMKN&o-= literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/kalman_supervisor.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/kalman_supervisor.o new file mode 100644 index 0000000000000000000000000000000000000000..591bc7f5c64713d56229af81fe475d91738eb534 GIT binary patch literal 2040 zcmbVMK~EDw6n^cZK}7|P35iJ^q#+Px(>5^yPur3LCXEnV^&rW1DNDMs+pW8UfrAnM z0o?cj9{d3&UL@h*!HZXafd>;$-t;2Ax1C4FZF_N=+3&q?zBh07&D*{%SC-SM6!1vF z2k3ds0{j~3*;Z^?Fb0=Mdyvk-;WSvkr*PK6Iz~J;tf@>E=cEvsF95YPa^vE5=35GC z>tZ_d7IA^s#;oHUu8qWN*~}-@!#Et?g7lBnpVOLv{YNK;{T0qo6ahY$=ortPmhZFy zd}nt(h+=%=wg4g-bZlNk-JAH#{g0V`DrSc9`$P1wvb1zx%&t6qENVf}YBU|MEw+PD z$fhfb^PMo*_F8C#jix8vhTI8Vv1k_N3%UHFnJ<W0C-mph%FWFYZ{`K9<a334!xDCR zx~mcRc{)gC47^DI1Al{tfjcF~jhLV;{lkEBedJ`!4C9C8JwIfhe*PvZQ_$n<TBHG^ zn%6b&AY9YxAeCYbaa`Ftxadq^eYg^gFBH#O=2ZjQ(N4z=UwTmxnhnVALUs#myW@n8 zA8{LYyRmvEd=OQoBi*N-Y<lfdu+!d(z+S1Wm5LR6ZF#v`uGzI>sZzF8b9>SY+GJyc z2Mtf|@mUD3;}u=e2(H8;@>ex}OxeWi@6USrE9g}hKqx))tee$%eg6fGr+qkwrSZ%W zwXX4`@AeNGX0+!^XA@C|U2L)yx-G|)?ydxL%aIP4n^6R27?4Bqyt#lbiQ)?|)!%^G z2z=jda|fuz{|N%)uvGuling-ofg_nke`i{!KBgYBaO&ekeIl!hynsk~xb9q^8O0~R zsP`(4^~yc#XZG)+L7HUzM;0WI&Y+JxI>Z%p673V^XA?Z1hxaMtI@!tm-&I^)Ap^&= zZ=o@$exvHcJWxWaAN3W-bN#BwQT`lGeXObjKGR9G`P@3D6B=^gDZ!D#i^yHZnaoe; fO1?W%U@7tyIoja7OiiFMDE>&j{{{;cCgcACRHLX; literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/ledring12.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/ledring12.o new file mode 100644 index 0000000000000000000000000000000000000000..df44183d277c7a5e5f60f822788c3dc5f473e0f9 GIT binary patch literal 19616 zcmc&+4RBP~bv|$36D&gD1!P<Nc=xR&Y()W85*T(fB&=2l%Ldm}$cf{))~;47q#*RO zS`iUsYX!1HD|afzWa`wOAYoGr;&j~BX;8-$;W!>TO=gIdy14b!62<`srzOO8p@FF1 zdGB87@}y0gX=i#pPxs#MoqO&%=bn4+&s*GGv30Xc(?}+bzDLtFi4sLNPnSbhF+@u# zhc>RDM8rkax{<1K5%q_O2Hw~8!t;10bUHStp9Tz~>`fF3Rv4jRxjPi}XVF0Z8DAib zeC4<=kayV^*hq6OP5gSYdJf)myNq5Mm`kBO7A@N5p=~bSal1UU$+g;KT+${dtLJ)L zop-t^II7pY#qx~mR80omqC=jcZ+^3?=je+GKi%ck3jAK^*6)XmQKAzr$YxULvjjQl ztp8DR`@M90=y5vZ+h7{NRcsuX+ksv7ZKxr-G;w3Hn)~MdG*6K?LZK5L)9*cUeX@Fd za`JYcssEFFSU$E1j9krnvVI$((?;mD5jwp~+NCITg3bDSA!n}%dzPiDc9^Lu=CKd9 zV0nApG|+RoCQ$CaV|%zu-yX{@EA)G4akwjExgSrgYwq&!BeckmC)_n>Nvs!T&hfa= zpN774^!YC2j|%yj{~YxD2Kr@PV#rTZXk@aSe(a*un>$eUQ>yBHU#jZ7P6IJdD0oq) zkvEWEm`@|`t)bvgmrxLXknP8K<*n!*i;}-Dqru;)lh#+`p<k4d(HAyopc~`G<IQ|0 zY@UnH=h49L*mg175N-Cjz;EL!t#c!C$UDH}!TPYhQ}9pFSiTt^qyg!d8Sq&Hed~DG zN6TT`O^~}n_-G#N#6Fr2JFSGh()lR&^Sk;fw~_Ki;IC4?40o!k;lXcIRX+ILL^z}k zT+lNL_iL%DpTg!W<2_;?ZHA1|uHk1{KL7RDnBUOmN8Q?%m_cp%UENRjjQacLHuwVu z?EZv7!6#uCKkS|HR4Ax*(!d-~xYOz%;}6+?oS%j9!Z_w;V~*tz#*TuyCIxwZ!6)`) zpgr64#@>@h3t-b582=Ao`?3tG&Vp@I8VxKkLnGhGphaAs(A|aeVe3rjFs{!(_Q|g& z|BSJ5J@eT2C%HWD*g4=U2WWuhFrXLPkbRqVDnC;b=<U+B?>EZl^Eepe@O3;>7{<h4 z|Hm_hS!0xOX$b!O6lA!u_tfy8_-TaYUX3wkIp3aTKEfZWITo<bBQ6a1lcAA~`PB9j z=4g*b>)<1cSuP*s@LByLCzmx(d5-uES`<y%{it+4$iwl0=QGnV?Z&Ot_8p8vx1hKD z7kxY9z(&FUUmfytT-Xmj8OVo_*LH?R?sSJn5U)<u(43v@Oa9l(R=W^~Dj(T4cF%^& zvCS)Jaju(2JX)?d-v7Yr3zX}915ctibVASZd(9Q06RpqPvby-W@ap<rI$;`gqAZZ- z&2{H{SGrev{q9n4{%yL?m8ttC4Bcn;YpZj6U8{3U)B7WXst-dBj(a`G4d}Azxw6%H z2Od~m4E{z=zIXG%@M<%V@73J7UfrGNC3ms+T$bTGWf;CeGJNF}@aE#t@Wdc%7>^$h z`vu!mhuvMUJIAa;!k&YO>nX(bBiuJ)`ylkEfFC)X;PEbp?q$%Oc`=P2`qtuM`9jD~ z8Z=T)LG&B+9yVO7HROXibmF)5?<2z+PZ?ii&a(1zWAEP|<+<_8`E>1<m>*aw4-#a^ zUHZ)`*W2GqXkQ$z(y=zN%=y5Kw_i+DpnR@nxN2Nqa?C_I_I1Q}<Y7F1tU)Ga`0`+{ zGSo4Zy{#te67+`89D11b>&3(C%>-gZ6Hzsf%S3taGPa#2Y{$OnBmL4T_}(w)hpye& z``R$eeq-<VEO|Lj{&Kr^^drdp@t0gj|1+i^&4G^*bh)<EIQpyhjH5%hQ?+&=HIj?? z9scO?u@!jttga74bXQ-;&e}k9zSg${@pBns(|RK`GU!@T7}BYbZl$&BR$$$NEzVv0 z)|<6oe)Wn`e3$oda_q{!oby+ns0m%myk0(5_NT*DZ!e_9Kh;+pyYI2rp3Q^4Z+R=m zF6hgT^_9B@4ve`5KEPVoWTvVXJeI1u@5ZLFm57OEclXmvM}vK}jln=fTiR#9NII_r znadL)%;7;-uJ^6S7c776mC%V(C=>f2{F31NRFLZ(eT7b(IuIK9!6S5y=jplA{=P3j zezPm|H1-h#rw-5vLEq0qhY6y-j~gO^HPDk~W%)h>eWk903utX!<{jH>AJ?}JX5Ko# zH~Znj@+E|ID&ttVYu@sVg2%?F^^WZ^lvh$lUvF2|@{^Q#iP!2FuhnZekM&}$j&Y9X z@GVrm{ucL|f6mm`OfGD=@}H0AZ11@`S$!(xvf?Jkja-Z|uTgnC#+to<IEA=z;YDrW z{cmdn(mt=jKIa>Pf#>n$VC;PJmM2`_!@Plw2=*+~w10f-aawLt-nT3}!9L*v(@UO} z-YC|jvImbObj<Tcl<&p*^fO&6oQw6F5L?4;6aE_T^4zNI@;~do5q;YI*uE{{fa!H- zxaU{8-CNul^ars(uGgB^u=9C+&an)Q=41VR)75qK*`cn&XT!XfU5`E;HeB=lT~BOr zxm{a$ZQFu1t@c!I-w@Wgl_(Eked}>)eeYvG(Sto)FUD!Gp>_k$7kl59=QYXY<Nci3 zkhcNr;y`y6{h|l{?<=OZH(<95Soco-3iDxm+0l=`6o${2AHBA76MVhm=#9PqV9gJL zohS6{WBV{CtvOCuN72@b^RPM3D|P=?gZ&%tYnH&i-G2+efzQ7OpO3-kyZ@L*o`=ux zhtCuIeINAJ*nVB#f0nLq8jCzi*FKGL%R<|Ke_k6n|1~Z6RGDkwr~1NU@AYZH3wqYE zA7Q<GAN5OEFOS$d419of@gmm2Z^I9cLZ)HJbW+Q(<dD8|5q|S$`uMtXj4@HIm&eh! zAatdcV&4koM7*w0t(V894DtLu@c$b3vtL83yvvL6eY2-AvVraDbJH&j_^oAU#B-B$ z%f^uga|6$nLHJS%d*_dM-2(rKOV|U0AKQ!fod)F7E&1$q@lnt{wE%lbyq~13OFh^# ze-YTYzO*p^mhQ0(*aG|Dz9SfiQO)Q(g7Llpxv(a`In+?Mf&J|eWZFk_XUIei`5P?1 zxHwrI#(ZU&ZtOi_$7jSkj?W)2p=-Ay&b{KoemWQHzCk7A#(coIeHR$V!@+Q9j}^NR z%TDR3s=@n0dk(r>TMmAX79aX5wH^F=&oVAE4PyNg-b4GcsBIMMj*0zI#>?fw{h8TY zPNB{*{@|SK`MH-vBX#hpSiiQ2*PI?NEp{W8t>U=|TgbhJ9k-23Ch!{UNirrU@0M|$ z_wVw(AA5{2<`nPUYp}=oA=ZJ{F4KtR+e<j!f8X-wcW1%;n7=FWXfNx*w_qcU<31ig zcp>NKplbsycH;YTZT}{`OWjE$f1}u!X}P_$FWZvW7q<DheyhDMf-me_C}~wZ^x$w+ zwEoGeX!h}hhV}A2YyW$fcO2^^uL~~rOYA8K`w<V;!<V41jx~|64zfLC+YT+8fUWms zrK%#Z^Lah5kmqkwqqX^%!+BUE_^iNl*@rn>2KzZ}l?ytobvSoY@Du1J*LU8l^BOPZ zmTP@T*oy5n!RvX;@v1qHo$14PmkXKWkR<~-`vLPSH!4=MZWA~!`?2RT@C+gD`rU@F z7<%PHr>CG>0oL^WLNDx7gFeW`ZDpG>Zj)oT$y3@y(Z&y3SU$t^j`vTPW9lBjifdE* zm+ASD4Y?2UyeJKgl)102x5rK^<oyA^`v%^zuD2oX5B{vonj?c(%J$rfy5%#--`|*8 ztcOz8-iG%l@4DP2rw>1|te)ek=5BNUc>l7Ku8f^80-Gd#=Y=!-m(@_l&Wgb&mYqcX z2<q>;sLg%kz{AF4+LDtfUwGkb55L!?EvX@DJMzL44<AO^x02d=M-MHV#2kqsKZ!hy zyoQXn3Qx~6?3aVxD92G|TO2|;1M}wzeh0g}3%d*<ZnM6rE9F7NvPG#YdQh$na{erV z-tC~_vF9;lAGdVH9FYFN_`Xsak@lPQ{U^%Y`7e8(%06x$kH5P)UMaR8`lLK~@h*MW z&wkI?_2H-KM$a5tn+bojbZ~{O@t7Afy{SyQOlG0ijrtJcn|oe?x4=KoM`c*wF@`*^ z=D{yL=BK>7=HN`{$@9*~x}S}>;O++x?3)hGp+%vfP46*RdB-uH{-p)p`{ADv;QklL z=f{|Dyso#g&u+x{_y-RyGvR}WN~sO^M8WojG!QxG3q-E?0(|cv?R)XAa_F%MdW3G= z*!zYRt8Rmh-<q=ZZE0+M+p)tg&01$Uj&Up+`a};7&e29rV9w5iJ*1AT+oo%i)v`YC z_|T)DdfWf#4?t%wwe^bps;A1l_F}^0FZ5<|j43Ge8i>6XzH~UD!6p`tyQ0jTLhoOq zZ4_<%^M(^Hypwc=Xv=$iZl8&D^1h{h@AIJLeKyB(4d)OZ=b5qI-oMFng+)IX^w0x7 zJawPN=L8dbv%~N|>35rpHwF28;~&Sm?bc4bhJ8|a^v=G!$kmtEP#ZXhHE;rZRoSn4 zu9D{(=2y0MQ!o_R6!c>b_%U`o7dCpRjn6S<YYn_Jg7-p)H-Ovw!tW+(fS>9bdKP;( z>n`FA(za|aHiEp@ng?1wgAH!j6g-KxKKRA>?T3~PZZLv_AtT7TTDtLE!oI}sE;~_- zc()Q`^*U^J^L()5lRU3*Ok#WTIU1|hjB_-{c0Pa0xtLlP8X28)b^TPmFudpD?R10Z z0MCt7sXbS;{&ilDA9r}TJL0p|6PPoR&f`@)raV_P+zE8!@Yr2MK>`+qZ$}rR{u$&? zQjq1}bt_f#9EpAo*nN0DPeI%PWV`zB1n*q$&$Dda#v;yhz2CuJ-_@UQ@n@cS2Q;7G zt@&EP>qp?leX<Paz*Fs$`&$dXGB)v=tHvkZ-|+f7TO2xkn>}~r`p)r;<JaM3HqP_u zW9%PN>u!!w8tVYNd<VXHlgyCU54l<9tcAAChV~3w^78r@!P=z3kJyH6GuDOern3#9 z$2K$1;>qu8VP9S|YGGqu?`vUOUK4q5699kMqpA*NQ}E<7G~3#;Iqc2nWwtrX$@>E= z0bV!Su^$uG#K@N^7}<?yA6aq!;_V!J?0piq(aQW@+;duE(=^ZSvk(4|A2Pjs#_mN7 z&@f*AfIXheARqOT&+-jmEH|(7`*G*&$3CUiT<LAXxvf*kZJ^BYDL>@*{v7#3%x^wb zhan@M=|_R(_)YHz@a>!ItN6rL#A)Vt9=<sU8%N<A>=$h3zd(Dnoj%X))Beb9jSJsD zJ;3iFFXpyy4CMg$)IksC!#utXjQx%MSo(Gp;}OMJM1_yv58DvNK=p5K$8w+kV6ytF zD6@R;|Hq^?cX+J3U6>;nZ|<WT<Nc)Qhx>JL{02VNAKpKX_bgjJ?7+Uy?|Xsq7<Xf= zyD`q)7~?+y#<Hl`0br7^v)=~1<NoTA&lX=WSNeIs%5map%pDi*zN6l<5uERKo`#*U z2kVb+E*pvDW(?GB)<$9!x`sQuofC5pEvr3SdzI&4h&H|zIad)Rjqb)B^gs{pae2KX zGXwi#dryvj&;=cg?k*c4;<FhY^fleyRteh<t?REk)%bj3-%9Mwt=JkLGgGeRzJ9H3 zV*jCsIW{xjeFn~u;K^-&Q$LY?#*_@~=iE2Xq3+$<NcXvnAp2o<Hj6_WCy_WO>Moyt zY@FZK*KZEh*FPEJGAEpQtfaYg1F@Xuy60uiN1kkq?c^6tEwSy1-49cHGMbE|-nxrX zqQ>^}mgeSoEE&g4MoL8M8e2GTZ*S!K?%HUQ^G^PQv|~?#U(+7`gY;E9qt?b`tN~^4 zuWf8<{AxU5zeuz+HE}7~kmzU!r@FW;Pi<^#ysoOTd52Agb}g+n@+GkLJ?+UjWNc{M z(a?m)5`uB2lP^(E2o~}BdMH8EEDG%{O^tO`LMd*?^?MTWcrz-p9&YMjTX1TKN9(M9 zDw?CUO>v6vYEAAbZ-^##*cA00O-)Lb>Z5h>@|LC+p{7-@Zrml=*>XzZz~3}Yx7+P< zxvbuP(;t(_LpTDH;qiFT#xRU&h)6I9g(gii<aUGfH>Pa7mCtV^{C|G=Di%yNL4S&< zz;7w{q<KF#4W3Gar{lxEJzGl61_DdRryvdem($?s=>M<qJJa-=4ln#2=~HRwe^>jY z<3sn9mw(1AxaapDG^<-$nqm#n#%8m=C1EBT;%3?E)<jEvV-re=SVLnH5uzgzH-kl` zt4oVZf<+~zW<fNuYc)#6pZXNzMI|P`DJd?!JB{E1){q<Y3y#q<627(0z!=c+-)u<- zCudq<0W<mVe0M4Q`J#xEiHC7nKgb|b2_D9a1*_*Qlqf9lGXlq+ZYt@NF;$iYoH3DR z;@f~S|3ML#p0VicxyyJ+sQj|Pc`;!8vcO*#_+tVe6{dJW;QIyMD!RsZMJqima1s+- zT5w3<9)Zh#|61Uq0>3O8j0*haEEJF;g8z?DW;s0zEtuZ1Gde5q%L4z2z&{lDnOkh2 zSMcG34fBaCvT<qeOuT2j7>5Q<tL%(!6L>`6IQv=&`!9>Wm4i7F|3E<|o#g5-5h8oM zX5zmGKAJ+GFPa1eF5`;C%LUHk%t_)~1upjm^X%86-<f{?phZ88qiUr`1up9{Zxpy( zFD2eCaH+n`_Y2%D_)7dafs5gtnrSZ!+~c4h6}T|-6#bh5&vDSdC-4;x{6m484*b^w zmv)qLE`XvM;)Arm#Fq+O`iI2x1zzmnUn20e4jlKT7XN?)xBWzN6)%x}*5Wgb%hLS< zmv)x+cu3%;gMY2SrC#~seUreQezjZRNe3UCA0WRmwGWl@{E@)B9Q4l!JmtWT3cS~W zj|lvL1OI`*`vorL{}+M3;-LSzz>f=D+UdH$M+Gj&bD=dZ27M@SxQCT;1%6r7rM{mQ z_(u*rAn>aWyh7mD1upqNC~%HXoFv{La0$qMI|MG{k;Hoh?iLIr&Oheh@yZgo<o_*! zFL2<0CGdp~{ItOF!Tu&W#{}+i;O_|>2P-Q{d3e2Hd2$^1b%C#N;078py(#c~n;qeP z*TOeB=<&k<3$Jw07Ye*p;4%*3M=ch8m%v44^`gr~P4vl`Jx^!f&FUnh?{ov3ekT4o ztfQJjFXI8X)QL}wHz%9VOq{87T5vNlYBv2${Iiz6(|D!QQpXjsGueD*;`ds7rtzEk zh(%UmX7ibef5GB2jho5<=p+{38GL5qaf{D1ezQEd`E#TW(0d#hSMfo0R{T&J{IAmB zucpCqS3E2KH`Cz%mIgnc2LD+aocCFa;c;i=LLu!8Kb*}Dw*g<I`2RD)R{k{ftJ2`b zY4G(H|7m}g@tK<9b$nbeDJ_aoekXl}j|<yd8=EWaiv{ccz&h{?V0U98*%58JKfX%< zwJp)4DCXBujPC~2_EW4%sjj61R}AXQ#suyqrmhqOmnn(vZEj4Gbve<{($O9luamfK znC{)a-`S4aosM?v@<vJ(O(x?Bag!mj1Yf8$$J^Tlup<%O-I(07)w*Y?ZHmTriWd-} zI^HhTN;WphqGcZI`o>b!D%IjP#VRDxq^1@3MpKtC%I%9)v@Tv^9SNwN+>DzP>*l02 z5#QYi1*`eeC285ZX#Lu?r4)<C8sc@5j<Gc)8smls^)>5c-MZmnWW7YVD+U77S2VV* zs&O-RFSicdjoUD`T->g%yXo>rx%lC`uZJ4ZWX<}!#f28irE95n%AiH-OChirxm~!x z!Yx)Sh)UK{dq-^vmrA%)%B51ior3@+wrrNhl(e)LdId#Qs<pOQ079#^C19~jc*MO* zc^hmQ?ttqi6tJoVN;bAME0AS)Auc#!0<^Q#xb$PMsn{J)Y;E}p+bDoWENfuBbp`lE z+YD>0%ENZ$W;?7|zYdp+?7EFnz7J%xt%arep3tJlAoAs)U3Rn$t|!Zh;`Q}4&9%^h zJ*qC=6x~x3Yw2i)Y||HZHP%ZBTb24mOLKCXLR{%hcU@XK-F4}jsXIf<^QGU^pl{q4 z6s^BIP)xO!DY;x?PsHtwJDQ_SLP4sjX=>TgUX$Rv$QpQlBD$;HzRaAe-TY2mV77KN zwa2$5T4I=rEs3(`9Zm7}KR{5yTqI2N7>^DvRCl#fXLYoF=RNTxJ8d~z02jJDP=By- zs(9~I>GRRVy>)_Ma}&Z6wYMdb^_T#)?e!E*Mw{!Ui<Xprp(U{s=B&AA>jUAktu+s9 z-n_k{x~94;ytSf+Y#X$1#?9(i+Dii^rQ74pbyQt?Kfz1d<4Hoygpbrrg{rA5T)EF# zf_N{_MjXmz%)ixvKPTcm(__h)N-rxowrW#J?z@?fiXRsgcR2XSeW;Va+$TEeA3}Rh zPWnd#&i$%#%5y!_XWC7zzdupvRs5{LCB0mS-f_@Nd>H2kPE4=b^Cf{h?TPOfv(j%B zxRajuyPTZ*x&`jkH#-gfOd9;9H2i;<20xRAkGz6%%ES8rPEK6j8#(n#rlIc?IMb_s z)uqs@xFN1sxL*~|QgES)C0|OxRr(jw;HKE}F9(0|>B8dkj=-IIjSJjqhwEwZRl>oT ze~ZQ0{&QR$9h`h}#Ma4)n*w+8sZK*55dp%<=XHTQ?SERKSM7FI;M{MkBL6#S=r1bt zZ3=ysIGQjY`AvskXA9hE=M@5X%D*ZN-k%2liNc@bgN%=79k|>+zoYO`>Bk+oq(3ik z)~j97_d^GNQ@p$EzzYQak%Paazv{pxJ&F5KXTLcDXM3{z#e)9|fwMhTJl{bd67&TQ zdWi=F?(BDif~(`c$-%!;@UL|6m-se?k800q1($bM%<3Zte`%lV4t$&FS006>9VDJ5 zj=U0=d^`eo>YJ_Lsyz7uch0W@g}*w#-bq70o`(LaLa)ZX>k7S!ONVFqRXMZ7L~!Cc zY49@wch1Ml0+;?45qADap=W=S_*Dn}LxLWMQY%UOOB}x)vXayOSpt{+HrQn3aqyA& z3WZ*^kEzhBc)q}${jO5@uwJdA-(rQ2if>56C#mpJ`|VWtsQAG&_;U(>b$o}@;IAuq zhmf7Kj}&~jf<Lm@u1Gtl#Jh;V<#<WF&OzTP=$jn$5^oi_)6Sg^KK+7EmxGVQ52WEU ztl+A?$J5|HRPe8eJ~?X=S5RyRbzD*ccg~Amg<joH9#H62{EULD{0p*eA)Ndx1@4q* zYa04tg<g$6FDdjYeq5nf<#|=1SMk#VcgB;Sq`{vOS9eao>KC}vuby$xOaB>k&`bOU zg<h3&SfN+(mjv$g!&ekOJg=p{9as3M`0Hu-{LsPY8GBgijDwHF-$}#gY>wTK?Z)F3 z5PZfJT-EEmz@7ecQQ&+oQ~6v~_{iTNaTo5Tc1QdjQ~oB2kph7``G*9)4D@^Lrq<t0 z0%tqR*vT)pDR`GcpGw33DTSWDZOhc3hJIM!PI+EUgG+w=zYgFdp!|;P7B3_&={yd6 zP@EfuIZ4vX@5`oxUVhh>`wmGT5|gsnK`+1W2OPNc&yWL`-@7Xvxctt(&4J7F_CpSQ zR5(|}fy?jja=n%E7sGy>TJ3Dw4&uDm>A>ah0a6ZJ{(j(q10NOVE~&TdSN=Z1t<dv4 z9TxQh1-FJu@DZ>j=OeO$+{x#%cxQ^7`(^%}LSL0X522is>Uc5z0YUHNKZtjnOzSVc zDGC0=qOS61-ts$_lmBr+@8q9O{;RX_SL1_|KR!KJDJ0sloGi}@fp1fA)>nSVd`Q8C zi(5#8f-}ARp4h73OfT3|O2L`FK)g7h;7l*3BR!+wOdk;Rg9^^_dj$Tnf-}AR{&-x$ znZF#5(+bY?4+%bJ6rAZ-iTb#LGkt@gzo_6WPp7C~RdA-4{w58=_GkWbZz1)N{&PU^ zcRTn<xlIQy<t|WgmZw$l2`D(rGcM{>)V^mIeyfT+nXvN)SxVrdxhNU$Oj1!DZcC}C zw!NK-5-nU|@{*!}tRiP(>kUdp__Tm)VF#FKxf#b#U^iL!rbUi>Q@b5*c8jd*V!LWx zCl^^ija7je6yi>~DAuxT7e1><J^z=viS}$taXmG~EhI{3#QG#(cw|B3%aQYVghX9t zXN&DpM4SupZ;h;e<hbVu!aD`dKBFejGP|}x1ySa{)Wm+wJe}>giS~~PKap)@|FT|! z0+W<VK;*Lh*VD9@a0v8Vmh)RQr;BVDq#iq)`s?ife!SuKPWfBK1bSwwrCo5guLL}s z{R1JJ{<IL3?axb$Y%lF!3v9Oj-FMjS<@~a1)9q#b4^fz{f9nT`cqiO|xPQKKboS4C zx!L*;iT))$$gJe7cL1HO|KhMsFZJa9`KnU3m-wFpo2~y!(SN1QX6mnOFM)5MFkAnX zqW_2><o@|8O}3Z)9|bmB|NZ~N{$D`*+4>)zrGK7^&i?-{P5);_|0WBkB-vg<-$h}z z{@vv^g~w&*tUn*|WqYarKLVRg|Ev73CXp)bZ0fIUFM&5un63Yu3Y#J#2)Tbg;>z~2 z|F?m0|I$xUv{DHFh>p{j>}=|<G>4iC6{l#pFeutz6!+u!$1~RbzO#Rx6VAEM?GJpK g|Kj&HVxMZ)Y*}TQbGGSh?K_43=Tu^prQ8z!Z(kzJ82|tP literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/lighthouse.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/lighthouse.o new file mode 100644 index 0000000000000000000000000000000000000000..0ae8aed52372ff57b114402443984a3391433275 GIT binary patch literal 3944 zcmb`KUuYaf9LIlmn`jmP#aOYe+D(m;YO~}H3%TOMCYL`aoJO0I22?Jay@|KxE_>{4 zB%z`wC<?wLH27p6g|_(6xAvhzzz6%R=yMf>zDf-kA?WY7Gr!zqZx?)U!tL)jpZU)3 zH#@U4yZLy!Jd@32fJ+8$K)1#e;O>K6-;P`x9)|()o;Yb5Kl5+@;&)f~4cNLjpSd~+ zu(_DE3p;&qc6Si=!Ypi|ejDR&qTL(<*y@MQj{x>w4XuH{Y`$}zG;mDXEb993_p1Rf zes&7BKE*zyv(cW4`oi{~*hYPJ4Y&p%`}KWjU;52Bdad)3eTno#O1nE~@0qAs%tGPb z{KVD$i{D?_F{;0mOBex5L)0o>Qv|XGP!sM7`Acrud#@hW{k67u8SCxPZ&kUG#R-<? za{Gsu1}=XkXZ6-&2_i&zpZ}?RlA@}o@J<Sc*<$gWIWqhDTV}=g8*bh4R?THUFvGeq zCq`R=zw9;83*5RF3O8H}gjuliqxrF1!OG>$5hrMlqBnN>G;u3uQcG?ue>N?l<TML? z@W($%DkJg912FI}sTde3ULJ{noNK*}p46-sU+-x^zb=h@GrIQj=a5qzUdEe|4nXSl zsInoCCZmm$M^;e$h?K#CvSbXnPpe7Sj7%?|MxN31BT^n+4dCcqXhv=?rz0Sv>BqZW za6H=PS6s&F<<xAzLrT>(X5{wrIpi5lU+Q+jIC3>L1n**n=U(Sw3jaKXUryoIQ~0eE zzLUa#O5wk!@V}7{X!Fb~G=S@pbiZd(_)H3i#=-GrxiGwbaL|>U)mlTqa7|OZy6T1C zwIdVKX*jvIyo_gJQ#AcxV@fPTwc2t5r`eWAU^jNr4@8-d(8D;2R-G-+O-_`nb2BsZ z)0JvvVzNA4)iP86iql?!b-ES<;e-NS%U7^Y<B(uJbVARSl35W}Ja?t&udRkkG%Hp` z;JHP=*~EK;THt*kf@*g#@i9-~5kJ##+I10J2=K7ehNCr|7mhwfTFV=O-x5LSiT0ao zBG|x%)XH&Ok7HW>Y2^<h*G~&m@h4;ajN(UQd`$5Z$d4<Z485DEQ2hI)8(n!n6F;Hx zSCmijb^Vm$1>`(tLKVd+?=#9L^Nz-!)%c?Fc|81F*EFub`&x?Acyzw5aT+Jb=_pR) zIjMXyUufJ^KACOhlU^U^w;CT(KAD@!kFN_$=-i}t0v8?^@nME&c@GnRUgNr+?#ond zY)SvHVq`{?Pn_n5<0=fqbrz5RloFcCl3vfN$Jd`vetuX##tE(VMl*Dlz-otqv~~6Z z(QvF#tcPILoX`Plsoe%E@To%boHdSB5=8_(Z0sdg!*`tqbKI;`(T=v_J6eW{&Lu1Q zGP7Jf0tB85|3fh`22Pdsrj<c$Y2dc9Z1goCMthFt)5f1(7SyJ@L&32;ia&CB-FUrT zP(1!6bVT*T=0hcp=^UY$Y5f-u_3q|poI{6V()WyBIR7~vqR->!ameqK-uxvc7)j~R z*hVL5{>C4Wijor2{Lxnu=jZvmfQ(Yb@4uz;^Ye|8sBnL-(?2Ci`8x^usW12E{64az z{8v<d)^omi{r!~uw^e@5L-$W#W!#_nCbFdb*H!)!w(EuaGy4*qr2D_4@-HeO<)^Pa z?$7zZMn<U)&JFab{H5~0EvpAtg`++Msjj~dSh%3zrdn9qcl5rE=ci%D*PdeB?WZfi Z3MZ7+gS@I5{imDM-&UW%->@*H|G&aHTMqyL literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/locodeck.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/locodeck.o new file mode 100644 index 0000000000000000000000000000000000000000..cf0e4bce1887145027ce18f0d83298384cd4a9f2 GIT binary patch literal 6896 zcmb_gQEVL56}{_$kT#|@*#x2z!Bh(1m}Xg<Kw}id+OcCJxy1Eul~h#Poy<<WtL*Nq zX2*>~Ds@{4DMEZWEg$VqiTFUV+Yh8xg%4Un=?7B#(@I5=`je<2@zD>8LBbzax%a($ zJ<o4vAyNCJ^?moux#!+_@6DSx{_*tO@qtVRq-EfBNIXFSKH8J?3#wayeQ*z4b;|GE z?>hgG-{yrsu5LPTX?+)LWC2zx1BLM}z~S{>g^kS%f4V|^)L%h~m2U!E0w`=?|0Uv? zoJ8*rs{_bYn#Ig&5enl!AArN3IGME!bbt0~7B=?ohur|(zmpDeZ#a9_CQ<jgvv*|j zw!%gMo_a5f90xfA_`^8lYW}BL;$=tHixaDx7v53zNp7-qKaw9c$JeojEOZwpv4(XA z*07Ed(xO_7{3AMlc5QO!7w1oM>#_Nt^9|lwJ_pAuz<KcT-h6<^t~<^M%@NhH1ILWU z{qnG$&)>Rm=~WlTUpWBdbgws@?3#?JjOYEg!GHdB&&%H+o%H#9YxM?>8|l(qm~opI z-oA1jW6d>%d2p>1&I<-dVK=QG7eHZneXAME7^Y5s=LvT@io(b}SF1Myx8AD9b+1u> zuHIU7@#<(kpZ_XABlJTOXogiB27pc+w#x#N->#pGv|S)V<h2%20eN0bzTyjrel_sV zqJh&s=O720;>ktyOD7i;UYZIg#>hwes6xK@&xbf+H`8vG_hnjd?nr0gGm*Ma*zBL! z0Q>mtr?#0?6rdm8?ZfYvm+DSy-82xfemb>2{9Dx-zC|6FId<#`cX;NR@42NgZ1^>= z-g3|2DvxV{J8`HTg=c8BPegvL9tVEB6b0^hZtT!lesnxHI_3_0QS%V?@&^wRo*Q-P z%4mM<u|9<`oI#6^_J7k@PM?+FK>A{JP|0qC3ZN|8+t<+@F!aqx2X5a^M(<vQ^y2ri z&Jah;veo?FI&o9StO+i!Kg~C*&_a(ZeuB%LJjwV@O#_!L83%eFF0J2-&mli!@MYb6 zpK<ZUYJJH{o^D#d7k>*2&Om}6kpQ#~;6`aRt<#GW%>g}|W{BqZ;)_Vi82n`;$bqjJ zp6+U$Uc94p5`5N(bU<c30kuvq{!^us;M;X}Cj#8lI=%Rc(n;{`I<lG)xnE&7$(rE5 z>w~}32mcG=yKzJ-XsN~8zz1m4^y%=Gh7aO;NW<?#ob<1=Zkz4njL)N`CU}YQtBlw5 zWvHT`rhk_CdETgpng3iL{zc|jm@g~rGUIK=CD$8>-({@lovi;?h3|lQ_6uzPiMYfv zq|C>C@H;SH8ebhW=>4Db;lMIf&o$`)@-!Yw;6PQ}QqYOPYb=H*+HpN>b)eo+j7Ga% ztc6iL@A+qgn9d{%fmb~iF13_%GQzE1du2SkEOzt(hWm0jDVN(`<TX2Gbqd+?)LExI zGk0QgVy=AR`0?U&sa%?voSQC#k0peSV16ma*GvRKJF2(hGwM#J@J?oec%tQFUGrfF z&sJdzmcP3cECt1&>9r9KO5WK3md>3nor_A|;so9o7FugEZ6;_1QQa>Ft!l62)77~; zjs+Dbsr<P9!$2pLtL+X&&++I$Gidtl^U!E_u(T~y7qt-h0mhq(3;HNmR3|yfR1D&6 zcs0VPsLb=F$Bt%5-AP9kNk_rXu@=U~!CbgF>$R$lAW}D84ZX2#w@#yh;G^3>T2T9W zab<B`C2tV`m+`wT{IJ2lgZpG;-zJ?04E!kf_abic3yhB={-D91;{LseKV;ytkJ<H9 znPb=AX58k#Xy_j_^j8cWv;JQ&PIc0|S=yW2p*kNH5bgWix9j;g<90o?-%%qSvz{Tw z?eW~lxLwatL&vO#_CacPJwIUFuIERFj#*FF&@sn{_CacPJ-;z@%z9)$w(I#b^J$%! z>+oI1?K(d*^dHeBsK0}}@7nV+W#FR*U-oaRCpmTD_Z0K@TX@X4&0p@rmsIqPNM|)^ zvi}oKXH9AH-m&?4CJ0}66$3ZdXU)Lrxx381JQt+%ZN|vR`G;`gU*T(AwuH+wPS8aI zC;n^f@3inP`@;s#L!}V&z6c*;o*2rD|IgWKw!Y}P%#iv;SFRII^DFUkFT$VY_=2HB z^CI!{22S@Y{wV`D=dots#Fu=MU-C-4Yw;`WOMa=J;VnJUk$krPG6%S9h2Lf0)Hk0y zsaN<b%(wL=-sS7U?>GLE!`2rca-H+d*gK6jj<l^wFA5r7E)JGs$W^`AgWTy(2XawJ z4$((*N6;mbLa=AK$j#vk*W1GJG%=-Kw7G3BS}lSn8e)emLav-?G(nwfa_U%P0y@SI zo6P{vN&lxt<BLn!_!85?1#O^fK2(SeF)oI_7ijDY0<gV!r|wjE^V^Fq<&k;b$2@vR z6K?L2bm=PR-9wJiBwnCzVTUj~{u;;2IugDePkT1yr~g@*P2zuVg4maMilH`*zqI;S zxFA{Iij03GUi<=f(#G#Y9_WvlNaIIe(GoA?S3)c;zsnEA*7|21iDws1U?(mAwYxN9 zmWh;~VkKVkHxNt9e~R-9pJle<#b3luT7H*5H6;(_r>}F-6Z{3l((+e0|1w@To5TzD zJa*FZAL0C0nMnBu@h9<;|CflR<-f-HXE|Ps#EbtDcGB{H#`!Bur2O>X0Ew6UzeX%A zzk9n5{IdM7A}uZdDSkOtv<y&wT9S5tI<KbXuia$+*D*dV{~Ia!X-Mq+?{fY;TC=^z z`JXjG>{G4OOlxg%>iQ5pY}ih*&fVC50DpG=uOMdcJqST<7yZTWAWK~G>Z|nao*uuC MH@?3Kk*yv7IfMS4dH?_b literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/lpsTdoa2Tag.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/lpsTdoa2Tag.o new file mode 100644 index 0000000000000000000000000000000000000000..e230a4e697b3232b837bce6a0be3b47be4c51156 GIT binary patch literal 3520 zcmeH}Jxml)5XawnsQ3{@qX~%?YeM3gxSP9E5I>3~ppy7SA|^x&SoRL@;&Hp#TO(Ft zM@dOZNl7OqrKO39v9zSb&Q9n5c1Ff^sf>k*FS*Q{-~Q(9?AzlVZ*JeebD&f*GD_y1 z*~^4dJhnIY?bIi9)NGe$KOs#UQBbGYxaL-oH>z&U#+nOk8g=)IjaS^OHePjyZ5(z- zY#ec~A%>wXr)bM5+H#7voT4qKXv-<ua*DRxG}^rsEg+%=M6`g277)<_B3eL13y5f; zmqzidJPh^o7EKk5!vzfJKhHMiZ|}o_efIxf;miB<Z|;td-*75-A3kxWqo@<Mf_B$g zh!Q7lHJvdxPNIc&hh|CGYNyRGeVH_!>t5ZhS8Lb3THUDx$)ZcM>ZMEIUd_RkTD6}2 zx$JjW`#0ZbzJ4zf%Ec#wDVyTmF4L9#IB7xQ$wGEtUN@&L*^mFe{#o)%>b?WK;zj0? zJIrq|&rTa-gyVAA97OnKWc~ckACOg2eyp~nTyPpZCI7VA&!11&iF?yHL#Ko1UTB7v z%uvI0qUU4XuoWc}bUFpyun98WiNY7-QIgQxZ%19AC$HvF3u~giuwZ6q3HJCHQwu+C zrjKG2^-MoM9ghA(>Pej(7q6l?dX{|~RUGTcKKqKp&rWS)rWA)i$oY)o@MYbW;_w~L zW5wa$;(S?g_|o@^;_!XW*A#~@&$X^N{0YuC6^Ac<ZYd6blJob9!}mG=pg8>doPSXq zzO1vOIQ#+5zbOuXigWpj;r+rt!+d~p40-P}S!xCqhd;=?qBz!{V_sDp{(0uU;_zF{ zCl!b9FrQHze$0GMari^bW5wYwF<(*~euepp;_#Q5uPP4zGV^uC;jb{?P#nIDEydxl z@`Y{1;mfh`L2>wN?0;4qzT9I+aro=(?<x)#*X-aM$@|@4+^;zNe&&OUV~tJbj^gl- zGOsEQe~bC3;_#0%pHv+FHuEXP;h$hWr#Srg%#GK3y_g2`6w@S&Et#dwrPO$hAPtN+ z-|HDKiIBjod83pzJAp?hqL=+&=Y`SYVzZmd%6}BkQ8iu#dey_{1ka|&fKF(Bfj+3u z|DsLgJW2VrOKR}@hIg5-pJZd|r<qOUy$i<o9&2X*WeeRqcRubRJCl0p!zWtQzr%w5 zJ;VZ1k2%Io`e2WI`sneEe`+^*15pPg^>RMlBZga5>7&OgZ^$zZX)b;1$X~f%%w4Wu oWAO-G#k<SjA3VSJSZIa&kCCV$_Z4)CCPnod{0BEJBFB9F54>Z)asU7T literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/lpsTdoa3Tag.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/lpsTdoa3Tag.o new file mode 100644 index 0000000000000000000000000000000000000000..a4f95e6fb180fa842b3c89e970ba2dd9519a60f7 GIT binary patch literal 888 zcmbVKy-ve05WX}OlnJpRv6zWgB32T_P!@tJ=z^HS#N?(aiImipW27?i3OoXD!E^Bh za87MCa?Mgp=kM;j`+WZUxPN@;c^;VI!8dFp!vd^3WYW?J4B!x8I+@&%;q>X5q?}h- z!OA6Ba6x2|le=Ig_@b=P6IoHpJd<xCCu151aTtwh6q6wnb%0(t8Y!MeL}j8dzTWnB zd1^a-`1y6^eCG)OeCWB#k@x@M`@4L#YSKApS1Eg?831kGYsqGaQf#m=p3K)0=$uIg zbk;OLGhWyEQtqy~2XlrRbq5EQHnCz8cAl@L&T&?pee$Hu?oPJ;0!s#H`|2-ItJVzB zx+BrSOP567^zWkUHNUj(Q=_^cWooZ#oNfS)5beFIRHz#q>pBCbuZd64ap`Y$q5XYr F{U1)NIMV<C literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/lpsTwrTag.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/lpsTwrTag.o new file mode 100644 index 0000000000000000000000000000000000000000..2616de8729482728f3332653b089c5819c76cd78 GIT binary patch literal 4672 zcmeI0J!~UY6op^b{Dhxf85X3hScw5e$SaYN9saV2!YC}+0)e&3ibx10jx!q@9NRlH zQA|Z>P|AfWWlG9)q@YNdavRW=Dbv!WgL`J~v9F(<28nLpDtYgGbKbpo?l?2!{qfEh zpI@1pavW3ccQ;g|&YfHvuB+Ly>aMw~?xe8x*PB7%PyV=@)n8@*qqm&<CFrmJf#a~p z_0CqSv*k8hNm}nTqH-3)4RpoR^PYas)9-uw15bbG>5o+R;wVXW;z53D=BH+UYUZbA zero2YW`1hsPttC0jm?mn(%m?#OwsaAqag*}tEXC_@>&!xM-6G(xG%4K#3yLnm!Hvy zPtdq8KhqJPpmAT`ff1jeabMn<5uc!}4?KD4z)yO8{ONfgsD8@xM*QD>*t?|vmt8OU z+n+d|^1Lm36T2gDX>sx6ptSVm{a~frZ8w_rRwsDSjf1oq1)t9K;_ic1TUK$S*-E2E zDz~uUb~rybU#{E^EAv6A9&gXds(kAfcvuN=q*9*ejp>rSxGvAQzyFzZxG?ca;9Noe zO&SG><d3Tvn0)mM?pfdNiW#|#kH^0*{wb4pT_fI5PR$D5R^C+Kw9aS~;`BTYS#ZxO z9Zq?j<9typQ^tS9#916>^W%*3ds&<zuZ_fcaTq{X-^%=|xnAtlL*;qB&b`K+?Ow97 z8?V&2!iJmeyV*^-CCgLCHFn~7Er}jZxRVp*4<om>*6wa4gNK<)+|ze<H}craQTkOc zZFM_|8{}Jx($DlIKx$z<*X8_JGfJG%I$!rVJAzjh+x<ZO<n)ycxA7MYM;zv>8V*1A z)C`B8aaRq8mwB6p!_R#De4$SGUsm6q&aD5g>V3oE=XE?V9PwGlq2chezek3{&-#uH zhkr)(sp0VVRX;Wy{+p`L42Pd}pBoN;p!&ja_zzU`Bh3EHDlbaEFxa2pa_MFaNBolV zlHrJdth{VE{O>BS8V>)d^1Ft^Usk?qIQ&nPuNw}(yb@)jXE^-qOW$z#7jnDXHyr*8 z<&O-9{}bhhhQmLtdRmXOZ|qm#@j(6TAN$`_AM0YA1@%`=9MscOT{9f@u#c;T!{1WP zJdDpiG9K%}{S0F-`#t<Tu)q6;BmQ@)4-7{=?C+uB@aJ#i&K(&J|AC(GvElH4ulm$* z_>a{8*l_q0)n|sof1>_#!{KkMzAzmAC+c@Pvp=c&iiX2~uA0}M{%!S_Jioh=A1E7+ zdUn)bH5~Da>UUxC!**KVkU5R>xye-=wd-LT^-~va*3-HRH<HAKaTfyiO1K~rCV8-g z`i;R5JX*p=cY8bP@HDlW|2_q>6{mu8u%oJC)<RhqJ^hAg^rh<Yz3Cj3mA@o2@+cnM zXWvoozfo=KK7Z1-4>0aui0SWds-r(}<_qR0#<xer%)cFy4xbM<cwO}n_p^>Wy5G;g zulx9Sz{uQBU6sY8{vD~Ytbx%#TqEwEku}EG@`GCZ{0j&wqsBsWIoPk#;XP|o{xc+$ z(bMyQL~cL-x-g{Rb(Uo|_VpF^8v>nKj-9<0XU=oo&%Z0YC*WD`=YK(%f9?oyp<fJt YhA@M9iC&S#r2RGh{~q3->G${l3)Vte=l}o! literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_absolute_height.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_absolute_height.o new file mode 100644 index 0000000000000000000000000000000000000000..d7c99d4c7651551f9dbfa3091c6e6c50781cb298 GIT binary patch literal 984 zcmbtTu};G<5WNya%LWVx#9|~QT8UaoB!(h}Rt3s{n5Y;SiW^)Kku+7}N@e0l82Ag; zeg)z;_yRb$c59hTaFTWRp5OENtmNhV>SCo-0v#oIhb7W1z^6erXLJ)PP==|~`+!cn zeL||8>n^!T(>MrOG$eyGBO>IaRUc*PAd0cdf-n+15aW!K2KDQ{>out7lPb%SI#zD2 zCVA=+x#PM1@v^^N$?L4b*SF0}>=aHQ`IRC$^3E@Qd&U?;8wv+I+p&wpmeF^iNRl4w z=V?3^ychE5F%&d_g9$vbIAOzfn(^-FfeC&aiLj-Fmopsz&7Tv&`j|yF&!Mgap9r96 zWI+3Q4m3!Ugb#&%ufO6wG|K7MtOJ?~FXmHt!_w^|mVWzX&n%sW_Ddh)M&%#=BlOBM zU0i19{&yycweD}`qOavm`KBt%_bKC&ca^a-Pq2>Jo?UL;s|Ke^r<3lh@g^2U{#PZm Ie+}FJ1GmXd_5c6? literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_distance.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_distance.o new file mode 100644 index 0000000000000000000000000000000000000000..813c4c723b1d1b52f18644f8dc547aa65b9cff60 GIT binary patch literal 968 zcmbtTu};G<5WO~tmI>&D#9|~QT8Ww@5<{7aTIhn9s2CWEo4QIwlT?l?m5EQ_7x)X- zj(h?C!56@}wcE&Kf|IPf_xxVYXT>j9H`nD-2~3pW9X80Y03SKBy`<Yvg$gX3!6)=O zoeNU$-S){{nofd{MF|<Fg2<4Q%jQ(1<7k4F2*OD6K+XgwE$TOY*K1MFCv_&`CRT2v zp?K;Mwd1+|`KG^JspD+H*SF0p>=aI*_;QgPdFL0uyJT`h=M)ZhwxfnbE!TIgh~vR1 z$|OqyP6Ife!xNjtEa{|z_opK!`F$kAu2ulh>^YWfh*^qN4oxNbTmnT413Jtypg|hP zJdyTM{)7+FrKa7s+-;55^Ju(h>5dR9zkQQkOJ|^cvnRMw{fGY)z3Q7Tu6&sO4|x)6 z(?6e!{*E{8Tj;Frr-DnJRmH(7!4777cD41W8=PsKNv5yC`&bnDU$xMF3by|T*0@Mz literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_distance_robust.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_distance_robust.o new file mode 100644 index 0000000000000000000000000000000000000000..64218c8a8ed0be9de814fad1e64ae01f6b3e82e1 GIT binary patch literal 984 zcmbtTu};G<5WO~tmJJvXh{Z@q6p30%B!(h}q87R!21LccP~6m2BATRfT&Ya_2m^n? z+OI(T244W@)@~z{2~M)^-t&7tpOw5^USE|<B`{HfcUU3A0(|Dk=A3Rq6)G@udLPhf zwa!SbbJHbvX*vo*7A0hu3L-;JF6v{E4x<rPA_ybN133|#G^k(qU9UkspVXL$>sYzR z$BL&OQ9GXNpRW4bmAcLve0|%z!cO4?iZ2(*k#~OaJ98#CbWY)5XFK+g*v|D`D&n{| zh%(8NfcHe&pJb8-a5#l0Hi}u&N(H~2v)%E4Nq!&6u&w0)G<%LE>tmK;kwa5SK9xYx z!hrU(3}}$XF;Ap@ufO7bG^**>tpl1GFXz*E)6yLvR(|_s+m_Bi`=yU?qxuj333}C; zF0Oo-{ttN)YtuiUi@ugO?VIVW-lu{~-BrczBEbe`dv>+;s2iMXok^yz!CP1q`Cqlr I{xxj>4-HIC8UO$Q literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_flow.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_flow.o new file mode 100644 index 0000000000000000000000000000000000000000..da92486b8886c9a3eb522efc3c65f2724d979fcc GIT binary patch literal 1968 zcmb_c%Wl(95S=vTS%iQU5-f~ViBzIjP7qQH3tR<S7AOKlMG6bcO&lE6jwAab%8Kv@ z`2;?J9b3MF?<ijYGuJcn#dcOOQZjRn&pdn|{`~a${#vUAVlDU%B@!0kY`u&<6MC=# zm*Gd-|4Hy9h?8LE&$DoBo>DLv0vLY;kc2@_*m%UbPUn6#2{XT#?E2q@I%Syu#V=OW zhl76qq0>1S96GPlG#*94bmmOb%+XQk>}}7pbTW-G%0|&tha>$V3!Pon+wQsDUDfS5 zoghoLF><%Ih*w>Qo^;*bgH;U+p7vlJe*JDzwHtQ`pbcwHa^%}Je#0<LJ56=0&F0Lj z#;@Y*^{=D8W%ZTJ+sq3Vf0y}-rVqV)VfUH8QsD`<;T*H2E9R{8k5SUH^vf~@>(o!t zD|~*#T4$LDlEk0H=|?q!%~RMMn*)uTJ{}yE;m{oW=|~%zu0RnF!T00zeg4<MFD^kp z&BDX^IMCsnsgCxsLouMN2VK$g*31sa!e3+Dv3QzU)@{e)sm@Ktp2d@1`n|At(mRat z3LB%oq?dJxES~f-$K2vYOVq;RN$)ZSm48ZfaExAOg^wiC;i(3NYZQPw&T~*%N`RDI zwSzE>1BL6W?C**irAZRbwABAce+%>J*3ithc?|4#Bue&$AHy9CD8G7Ro`|60NoyP3 z6WXIy`PF{adG28@)$HNVwr33XY!YMYMJ98299R1<NrWc8KxMw*M;Opdo)GN6a=|mk z)R%6t^q2Gc5;>a1#h+~s5BSa|F_yV)-}IGSu;3f}OPEXFuxfwetM85!xJ;f9uuS?2 RMKzo9m%LGLMaaII{|6m3ip&52 literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_pose.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_pose.o new file mode 100644 index 0000000000000000000000000000000000000000..d2dbcc0b61384672c7b10fabf4f08a78502c0ee9 GIT binary patch literal 960 zcmbtT!AiqG5S=z+D}tye!OIGQE!ZUqc&MjJ)m}tASUh;B+qfmcZc{cZ)RRYl!@uyF zukb(o0-bHM?Xu>i17T*~yqCALB(E1&m(@xIOjO_lR-HisatrLt;SSWH2Dvx*gkHCM zN*cZEKDkZPaTK#;LPn`1D(2*@HI?Zo8Dk}*I8i)O&ytfi4O^ifv}q8M29u(NmEUY? zoCZWs0zW)i`MZ@q&Ki7uySVPX(hW3TEu$mu{lYirh_$rE@X*<fEd+Kg-z7tc!8FY{ zjo@$wPi!pMq?=0KpFT3h?-CW?;1qynFG8^)W+fLnHkINt1r+HF=rGHGMyU{dqTD0= zsozJH-g4bhcZz<wN6~LPyaVjD-o3$dhi6*%Mvrh%|A+n<wfdbtK6V)YdmF^s_}jVc ut9UPTd6D(~)bP<~)v>oouz}g#U5_3L1HGRe#@ApwSd{7C3ZnZ9xcVOx#6=wd literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_position.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_position.o new file mode 100644 index 0000000000000000000000000000000000000000..0e6d0b9a4da57201ac5963fe61d11adb1269b14e GIT binary patch literal 968 zcmbtTu};G<5WO~tmI>&D#9|~QT8Ww@5<{7S3Uon;fr^2lxFJ;{>bOdbR3<)wU*IoT zJMsnm2VVf^)@~z{2~M)^-t&7opB2BHUtUxz6);hOcUU3A0(=z6U`_{6hZ@YB!6)>( z-4oL6UG>S05aTdrNlHc{BQlQ2X?v21Q8LCV3*$sap?u0B(xHCacfAhve9~kYZ)4@Q zT8gJ0Q9GXNAFuk`l{(HEe0|%z!cOS~im#T*k#~Oan{%cxbV1=@XFD25Gzxu}3eE=; zktZ?{DGgzN3Xg2eS=tp@)So;s8Qmr_zSar=nm=>NhL~lx$g!zpG?hTn!hjC*9B3#w zk5XwL<xhAQU258O%N=OEoJZp=OSgwu`R$uLvvda9H+z5^^?&#e(W}1c;wpyee^(^2 zHvNma?C*HfzM0PIermYXSyk*T5^P|$XIESIy1|jwnPmDJyp2Vf|5Xd^r(pYk0GP!{ Axc~qF literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_sweep_angles.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_sweep_angles.o new file mode 100644 index 0000000000000000000000000000000000000000..87fc486d1f9fb4981ad76e1ab4b0c0a8f64bb445 GIT binary patch literal 976 zcmbtT%}N6?5T16$)|)>df|m$_E!eQTpwOOLs`esYw0Q7P(=~M$_orkd){}4H*|+f8 zNATo(_yjs>H|-Mlqyu5*`|^D|nXq{|JwGd#N}!_z@32Ig1^CF3?HS#MDpX)<4L+gQ z?Y2m*chM(TNfLTK3t}=#1d%=`oyJ%sqaegeczz(cCm#hTP3ksW+i6nAB{e3Z23B^x zu6XJYwd2_C(Xzi;spG7`*SE<lY!yzR_;QgPdFvOyHDhu^=M)xpHe(x!&0ODwB8mp- z6X)Xri|<38QV;eg@W8@|#oa{k{`ihbejP~vQmHyK5dck}BguxCrI=@5SCUU8P;@b% z!!!lzB~ip<X`bkBco%JI>Q%$u&hTQc46hryJ;cgy-sp*;)6l%(1Kg<o!+(fg^-UXB zK6L+^Jc+gLpU*{q$y?@|W?9`&1(!Ojik*3aHO%JhYU?&@aGdFM(tS1Fz@o_inhDJ( HVfudnG`&k` literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_tdoa.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_tdoa.o new file mode 100644 index 0000000000000000000000000000000000000000..cb8ee1445917c7146ff29405dbc1607da748677e GIT binary patch literal 960 zcmbVL!A`<J5FMxyjEPZCCSKOWL`Y=QHt~Qb2q+h$7l;QBxRfPrWGPwJ1Wz9Q4gbO` zU*UiF1v(2|*sMJ<$!6xgzSo)AwC^`}x5YvMOcdY?Hps953yW+l=?0Xc1PibK4V_l& znp8UXJ<?6naTK#;LPn`1D(0kFo62;QjIokYoG2ctSIJ48hPBWS>NE&Rg-KDv%CA;6 zPXnT#1b%q6>F-v0oE`Z2b$N}w+zm8e%#$PU{p0tSjJ33-@UXKR2S^-Seb)*h`f8Xm z8o~J-Uf5W$Nh_7SHytv?9}^XK+Ye0uI(rj}4KORY%CV^wpDUm!XFvzD8PF&df=`q? z!dCbcU3$x1$KA;AdXEerI=VB&+V9?A+tC@QwRT(}DC61Ie~DiGP9KjQrvH;oVr}}{ xIq$3Z%zTS1>-#C;(X;9}StZ!R?9Q$qJ!cK{es-9?hC9L{&;OAL-Cw}<{{i@3M4tcv literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_tdoa_robust.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_tdoa_robust.o new file mode 100644 index 0000000000000000000000000000000000000000..cc49247361997ea1bdb972cd45665f88f645a7d2 GIT binary patch literal 976 zcmbVL!A=4(5FNk>-ju||#7j*~ghZO%jUMm>0p(&eF%S<Puq;b<BTGrQBzW>C`~d&L zE1%%W|L_ZR3R`IEo|t4Z^IqR{W}4l%>)V@rE(h9j@Ch5FS%5EtY%J*pl%NQULjM~& zt=1K(bnbej%lX(3Su`OdE{F^R(yUDdA4Ox#gdavS@a0Sdq)xq>=eTw1dZfZcT*J(% zRuxZOqE1}LyWI4*Gd0c*{QTOy!iCHY6razMBVYK(mzRvOw4o?qXWI^uC>wp(ia74e zA!mKT2eU*{A5Q1+!p1S1w73W!mTYf2WHNY+WY}%rHvwq!8cR07D8(v<I+MX%0!29k zI!F?rK9A#IBJFv$#m88vw%)ZaXry?(SBm#7-3ek<Z@*~U(rKu)rkx=up>JD%j<xDe z2i-K?|H&jV*Zs|y^_6_2b&E8r_bH;QS(P2F0_<V5XIDqhX@iSYr-SaR@c|}T_3x?B I{w3`CKla8-Q~&?~ literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_tof.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_tof.o new file mode 100644 index 0000000000000000000000000000000000000000..8830ddd0e87cbf77c12b8e9eb3b6bbb4920d9b75 GIT binary patch literal 960 zcmbtT!Ab)$5S@0#RzXltf|m%2E!eQT;Gv!>ReKRnEgn47blqhao2H~G)RQOw!@uy_ zukb(o0-dy*HpD&YK$v+i@9kv5=Jopard%q4i4uIk8W|Q~Zjr48-GVAqVD9xlq0??( zkXq-iN4i1`qm*SMk_bsu8k5V$Sc)VYVkM(AQ*orGGA2zLHbOsW(jX)?CV2xZzh2io z4T#<e{P29;->vj<HsI^q<u&#SC(wMkNRGVsi{D-_*3g#1!_IE(AhB=tT`4&4E0NF$ zj%V=9hMbMsLdL!E6I1bhrqZrR0O;g}D>lHa<T9tGQt?ayMKuFDm`s31g7bK!+ynd( zAEHlBx#{>@IbO|?<6TF0gjoCC8@zIK2D&$TiW}8`_|MR*zv<($!}Nc!NvutOI~V;G u@40WDXMH~vT>7j!4webFFuSwst;f8<Nv<==^fh=7iz5G9E_9!O>;C~l{6sqd literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_yaw_error.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/mm_yaw_error.o new file mode 100644 index 0000000000000000000000000000000000000000..863f4e1c34ad4590b77f4fe86f566cb0cfd4014f GIT binary patch literal 968 zcmbtT%}&BV5FV%zy!mr6@v<f+LL!^Ci3dDkDsnNNB*u8ar7meBWy!JzIQa@bf^XrK zqfg*__yjr&EnQc<=p>u@=G*x?Kj}U-FV2gF0%TTzSIDD`1$Z;a#++_I8A>p7I`7a5 zf)i3{UAD=U5dAP>@qqM%Br4+Mv^JEY7xxj#Fp3oq)uZI3PW_tidUfjgq{3uUL*!Pg znx`JoH=gSs=k;x*+gXE;Pn*}VvvLB>7gwbt@BH95=ZrD5k>Oxv+jfxHHtH@jlB6?b z;|`ZnNE*Vy1RhvFVS_+O-X7jF#jj%(-LP>}X8_RAG*PUJUde@zGNkxK0YwP|+8vF6 zh9XJ$K-s<gCEi1ko_5_5H_~`HPZ}@wlPB*Z)Ovf9XL-suWN-EmZ_EGCAE8!%)5T+2 zR{z!{5oh&Hzv}OJNp-W->;07Q=w7w$E*xy2w`bQ^cWD8;udHq=hpk`q&uOCl6m0z$ DG(1TN literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/multiranger.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/multiranger.o new file mode 100644 index 0000000000000000000000000000000000000000..53d37adf73b7b073c1279f93d845b3a1eb655fb2 GIT binary patch literal 11024 zcmeI2U2Ggz701u+CTVa&abl;5NLr8ElsKW;+KwZ<r4Q?mIIe1wuy&v#g5B}%I9_GH zG&^f-ITD+^@bN;H6p@EYxQGYG>O(4!u%HmD0jUp_sQ3~Ok#GwSmFPntj;JLpbI#mz zyT`LT2&p{Ijk5RN-}&Ej?mc&QcXqD7ab|2J914LhA@~{8dzu2g^O<@(?l$AF4_aY! z;TN|yBT#!V5xTX02kQtdZ{2~|yOH+gwMg4CN?$ghnxGo4#BWgj-ko?XytUQ$?p>&9 z&H9b_yl&U)_7e{#25xOG{AOu2lKfML5&5Hx*9LIC9EO^6?eW^fi{V?9Hy^FdhCg5X z*J0TB`rtFQ_d8&d;?@1B`K(0_xbv#l?c8r)UVkc7Q)3P?)AeKAS2bw{zPprII|dtF zaO{cdUbV&$u5k_5uH&w3ZT%qhJnRR|fq^>sbLZFKP}dX6eqi}F+bKt0dkWXJ#P(`4 zJFan&?eS)I%*9Q%r<&M*zqNI6bK#dC?H}#kS|oI0JrZ7i*ajO1FuycU@=dkgKg#E; z;rIrzjw4{>xD%-mOyYHO{XJa!BHB6uIFD`a9zJY~Z)`5yb@%aq)v5ii&ri?kC%ESr zBen|Am)aGN(KRCdr(5E&cAU%0s0(9F`!R^~35BbP^e%|q#hhet++T6t1Gu&-UN@v8 zO&WHzkmlz?(@7fK3$NyNp$Y9q4ep0mL;I&=T_r!bCtl4DQDfqK;0Wx05;Z>xLyXn~ z5Nb)`T-19&<!*D~S8BiZz=pp5Q@GwL=HkH~%JG|Sjsf>(t)+_Bom;#6N4_cd$gcDL z)OJGkcT+78%U~VB|KuawTTPH3)U}T%o-<x3WF6z_vQf4Q<)Up|Jon;PThQi~X7-VR z7sj+=+AbCxR8E=c%QT=;a)&|AnkEc(_R<VB#%YFFGM3U!rN=8dCu^I9OO}ni>=a8$ zZFH5vOOSye13?CY3<MbnG7w}S$Uu;RAOk@Lf(!&12r>|4Ajm+Ff&X6y-q`!`d|mY! zKI6lyJ{-;t4LxUco&CZEW3pJxrDx1+!I;LUa?Xrp44f?4#p!GgTXuRT>sV>0Vp~Qm z+IzCMyC)Xy={34cJAV>e-N%m;kM<a3>FMr0?H5pSd~OIk;2&GfRFS491^^NK*Q`X) zlec`z1r%j_p$C{@;XlXblg#;XBAgdPBd~M36YTZ5q>+D){jBo%S9s(w^AtX;rP9jw z7qLzADe=;De0qEt66?~_QE?mBdy(~8r|S%J4l7np`P_xp?M3--<n*vLB=om=zVxh> zxbExv3iH$>%D?8<n78iP&cDNa_0jE|dJ$kJ%H+PPc{cKY;=)5h-!H~Q;1i;!n#xZj zCu;<Fl46w7H}V^(2?_nE7!!d{ik@n|idAa^1z7drzxLt3_2Kt@_#>E~W^p@w__IEI zz=wa)hkwO~mwfnDAO3A0{(T?*V;}yS4`1=&Z~O4S`0&3Y-zToO-MAla$=8n|qG>of z2YLIf<&0Zq89!R{R>2u4WD-`{F>MD;lV<rc9L->h4oxQ90~5k1U<TPT^{fmw&YR`3 z+aNI>eaw!yrzO}Jq~j8-FO=wYj1Eh%PPm69$z;j2&3suMhkR-5^r^9)<n}oYn~s^V z%*;HD_fEnr&1%@nne$LrC-7t?Teu_^LW8tm0*_mSsg7}(l9%UkDfus(xK=j<a})~a zGMP<Z9x7Jw=%*h1Lcz)Az&+8KupCI99XmHTFqS+wGBR;yGC4UgICdrprL-A4J=ceV za}}plp=GBp4_3-Bn>&3f*E8p4DqX~bsGN1a;^6n64OYp{7My84)|IfIp<-b=dx>3X zma|NokvrcZ+cF&sGIn;>vXf%N#etK-m&0MaPCB_wRhQsT3f?XFQ-ag?3KjBmR5jh# z^V}x>wBRoZE{@=VKCh{?p?;rgy02AkAMo%+=H&kvx2akZT*kdExQx3ZxYVx-F7<B- zF7<y9T<Y%$F7<yCT<Sj%T<X^am--I{*Lz23FXn{`<wx%0A;FI;iTm0w_zA&Z^5Jtn z{H70I@!|KF)4qRJ#9b5mX9Ry=aJjDgg3IgkL*_B8=^jg$e+zw7L#+3PRfp!YTkv+~ z<mXwz4>70fQ|gZ}r~K>p4h`$`_&3<s^FIFL9{*ZD?Bl;A{O@4jR5`+r<a5j)!+A=6 zQ}~hZ$5(_O$rpv5@(`z>SeArd^0z$tQ6-1BJ$lVQ@aXmD%YBbt^H#n;)cdGEciNfj z{nEV8qfhaC`aOEhCz*Tmc18G+`K$^*lHX)b*GUh@q-s&{Ucr|HKP9-nzt!uVVcSnx zPn=R!V!py$=Rxb=5M1i-G5<9BQTL$A(Qfufe{x0bIqr7}?)u^J`n^DU;wgF&h4>-S z_xjiKH(2xE;!>Wq`+kr9Til0ec|Px$Q&>B;s%Lb|##@Z2W6e1b&CtC>bgEp2s9mHE z$$O&x5KX7^3X|Bi;4l<LbH%ioL%GZGOMlq?I*vAc9V>-<3lw$#AS9YD=IKUE&+uc_ z29Cy*ieFC3U0hYL#{0tEhI{kFXrMgCwSeoc4%HalrE2=wL~-<f={=<HD&n3nV8}NC z+I1nVEcDq=KK;gfxpzFhr-;e-5OzO`|2^u6qUW#u#L-4=Z=4mLe`&uMj7>dW({XGx z8{c(MDfD%z_1^KLXlR!I65kw<oeJfjevRt!I{y~3X7N)TU+Yok7H>a=v|0QWj<4fT zeEJou$7}vgWX<BwaQsoU%c93?b`2ZN;=jZ3Q!J$T^s88p*YVZw;_ctTG~_nNr{@;3 z&|Im=T7QNpi+XM40IfS!pPu)0;(u>^%8B>dp%KR8^oll*a~)S%)xB`D@!fnAsGsj> Iy?6Y704w+8E&u=k literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/num.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/num.o new file mode 100644 index 0000000000000000000000000000000000000000..4d9fd5f2d3727fd6f0485968050b44b455ae3d73 GIT binary patch literal 1744 zcmbtU&rcIU6n@)9ZNW%Eg9J=FC;{5gwQbY@A+iM(4q&h?k;Fr@ZFlX)?v`$sq=qJ- ziDxwNj^6NuH!sFC{sksPJ(GCo5jh!SQ{R+XSvJLkzGn7&@0<5)X5V)G_WT_e$AKjr zyn`dlVga7F9qD3I6~O~;^d0hDF5ln1Qt>BJzxZO6gJf#VRjg5b&lLeS;vUq=^1|*w zcz%}yu4B5&-6NBH5Jp@<n1t>spZYSjEFM60Gyb~KNUj4ET^pNm*w~7L_h}#9_Y?ke zb9s9V7shatoe3CgPl%Y?Ux8-b>A~{}sB&Gg3Ks<8Nf3Y_z_5?TH}|j?x@YH8gW|y+ zKoa(M;(K5Dt5aB;#*j;-83#Xh;#Lk?f3L9>_fwx&TYY}u9>J$4$NJ+%;;XNHcvI)$ z1wp;m0rfdV2^U`5OO9fU@?yQd_Hi4z3xCdr`K{R6FsB93*UjR*B;fmoefACzUkJ|( z;{ji7IHu7Y^nB0;oyTmf@eJ=00s-I8M&lyP&df}Zk=eUTBv~lrGdW4siBd3#nUhH@ zv|<z#HIJH+$*HECF;@+lj0@3FG#nWhB2h9T8CnRna3DZ=AwuX*BpkhtC-{rdS!#pt zjaDvv%Si*^@z+Xt%;c0aO`_Gr(mbb}?$C}*x2<lDdGs)Th1nH`ml?m$>|TZf<Grl( zHO7x2dYNvAn<wzMkf;4DvOLQyXyF8Z&{s7f1A}EKsrtjb9L-621?VGsNI+iIRC7ty z&BzVN6!em5;Hw5jlgbJ{Rb7FsEM?P@o&`lpmz2YTqpW^EVh8Ji0)Agj=|enws5YNj zoBuf*4?^j&W=d&9(>TPOr5SQw5=^;lf{>L=350a11VW~uX|itGbNq)+FqXD<+L1$K z_BQL=+IGIHe%zo_CRz>*-E8#cm`(H3RBmQlb1}qt=LF;bVM}q+qv%C*{%d>$V`<JX zF1uLuAJ|FMt@?I!Iee%&$H*LWq~9G~&hvYabM}rDyk%s98aA=&T2vP*t>PEi{ZCkq I44v`60m}H=a{vGU literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/oa.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/oa.o new file mode 100644 index 0000000000000000000000000000000000000000..56905475c647a3ab8d1f2f64a4f28ae20a0d3c6b GIT binary patch literal 7504 zcmc(jU2Ggz6@c&VG?7UPq^*-!jipY4p-yNP+fAf6>ciS@99L|yWjn=?mfi90IJ?Sv zcbT2FY#G5Ic(6nzVo^{e`VbW)>?o=tR6!7dnzj!W>Vp+g)Q1QK38X%N6cnP?Qmt^# zopW}N@6Noy1K0ANd%t`B?zwkoX6HL+GNZ{vLUBu|U#r%LsZyI=t$tc})9O+6h}vHM z-TJnrR_{$E);pED6eQDw_s=KS?LF$`Pm*d?C4<TLcc%v*gE=sJ#Yv{OHjb#(BPy80 z@e|$3JKUkBA?BsSO0DK#em~8nNe18t?X=Am@JV*To}G5c?I;^N(X_FRSZJd<!d!O7 zY1wS-YL62{#z{8g;5u?v%Z_t{7=w4L{m1T24XxilKfJ!Z{Px<0mHjj7a}7}U4-Xz3 zw4f%)aw@%rwc)x%*|RO{{2lD2Pv*B`_?t2O8t^A<>wW&;UjA)!zj06Nus8mZ#47Ij z0_<z!HMRQDA+`0<=fe6WpiXzJ16OfPkoQ#_V?X4bn&)0itTN9XNjCf1=1H}MvD3TB z?px^}-LVdmztHbrEp-fiJClhev<b(ZSDhDHV~pW^U5p`)^Nnzvn@uczNbB5Q{(ZQ< zy=sfsmxJ>gD0SlA-t^Y?@>_bpbZ&csM@i~6;rYaU0H)6}$kkmcxHY?54HiIJ@Q*%{ z1HmNvf%(qyq0{z=Q>j#a+jr}}Jw9X?-26q`vFmQWS}E9mY2MwV6zV-!Df#xCSFQLk zS*ce&`~3KqUxG<!G4rEC&t<embAHwV?``HS`yKO5^VWQ$7GW*oi}{wdm@m6?5$U)5 z@0f3SXy)&gE)*ji#LPDxj1TEDsj3r7T}J5Qa*;G@A;<98(_ui?{c0@>Mz|@+XY-*a z%^3o}xff^u`}W-!)8zk&2QhKu@*IoNkMpC>j*OhPd(VF5oIPEwmh(lYRI%saNc%<C z9y(t0s&l0>^t^nr<hyyl;kou;YT)=lU;kjLf57f_y!qqM>pOZBd8*&Wnf|_klQD@9 zPJnz!{p&%LmKAyDQ_6zBsAhqusAj2MZFsjP?fg@kV^%xc!!S&WeEvo%a81(uE{$)K z+2h1F>A=u&R$<)sJP(6@LgddG93#$Smi@##Kw`7?r&6auqMu$GGan|-=YlzoQNIWh zo2@^UngEG>g~rUkMtqGpe;*3O@kW4+c?J6D=bEN1zCiqSg9pT~8ytrgRgb2$2<sVs zO8z<&Dk1bwiAhU!h*8)LJ+yP2wN!Xbmqwv}JO2SFC4@fLDfEM<XlD!kwDTW>T0*t> zm@u={XT&J%{tU#vHmcNbV)!3p_^lZJml*!f7=Ay7?}B}a%CkF$r(*a(3?Gi+#Tf3# z@Rb<;(-{5>;E#xN)jUa6CzV${1=X_%_qu6#q(I@+FM`152UV&gbPLeY<AS>|ijNd< zhg%rNn<2<^HT=xrtq|lS-f@-ZR4%xortWH8-2-hcwZ86!7TIjMdZCUt&uq5lc+Px1 zt8bXuvzhVXp-gssbad*>bar}ZICCbeYI$ey<l>1b*B@{AwFXAcUmR}K)k68?)8)QJ zoh&>N)vIN9qT$00!&7d}D^>hCRbPS?&41M?`BT2*`D~&GBe1qorBMY>i&%%Vu0LJM zUmU46V9n1DOsfT?&$?x2=^SX5*?7`*3X{0zmV@U@<uW{t`L0*zbahsgIw;PSE>QN& z%C6%P(&0xu*YRCd@Jb7=2ek=HqMF~l$6#OO)tb-l0fTqLdB?Wj;JqPM=%<JJD4wGJ zA>f}EypQ^Wz`r2)GeZAK!TGv?{_$?c;|%FwK9WxmNB^7~q8Z|t&r#~5$Wh<S6R-E! z%=H#StjzrNLmbSZADMqZ`kX)8f1fz#&wPcrng7eg&HP^xT-N!r@GtlGRpDROe@*z2 z`M*J&^Jl#q!avrZ`Ay<x{u{*2{NEK^=KmgXv;LdJ&HCRKeq{b166gGR{14$D^JjjS zxS9XIiJSR<BDl;SZf?4n`9DP5%zqzo^ZaxP{a%WN!Y0n^>ZNfHNj_K1S(^Fxk-qtT zA0uwoAw#?wmvWjg;}XXgE!fPsFA6{Mx{(tc_k~-5xS3CpIIoxWYsAgCD~5kw=gWp4 z=J4V`H`C9n#LaxJ82&qG{Bx3=C-ZB>P5*BYH~rrr&h>wn7JSq2&-|Sj|L?{4-!%NM zkpDj!{+Zv7@&AeNBd<UF;B0;`y6J%$>u`)>qUaU;i-Mns;prHjiQzLb{6)c^5^>9d z9~XR4@RZ<z;9nB_QVhQm!>`BijTnBLIGz((|2xFZ`hP6^@I6|mOFu<%U+^~>w+_Jv z7=qkKoX=;G&OxW(80s$ZF5>*XVEt~vrT#O-9|!xVMcfYR<Ev%7Zd@n-y@I13{=Ld; zM15L1X@&xMmmsEpzP{L`!*LfQ;$r>RNbi)PACP`paMZs_;|alWT`QzNBRJ|`qj6Di z)W1afHNjDzf0qV=qyA;mUlAPjuhaOl;Hb~nJF`A(<i|GjqxJ>;le#kN!`C~NsxQs^ z&MZjZ3uTde9z0B^e0R}Tse<D>Dm7cLtCUy80jl?>PQehBG=UyWrpnd4Q)Uj&{?F=1 z<P<+5hX(MA0tjj89~CM6n<AC3&d<B>ME}1wo7NuwPHuTiQ#VcLooDuOhvXrUSidxl zS*(0I>}}G<d=`dSW8SAOQp9IK<VF}3n1J+opJ=F`^U<fN&i21#MUot!armA`DR~XS zIktbx2*~z~&wy@J{$qGJq49YNN3HeqI1Qbs`pp~&HO5F0>xX;9@wt940gH+sP<+-W zH%)sU&p;<C{uPSPaWFpmVt>rT_e|~eU!nMG9Ec>_GyW!YqT=76_%;<9<Kx>Pw&(cY z0~WRZK0452FfSY1Gy67lqT+vWFx1GABF29h{@I@6{}33)?}LBY7AgLD387ER*&(B@ z{~wV3$Cw;6{NDAzzZoCjr<!LUklLj8^S|PN2%#B6c&8F=e~K1(SzEO}O#A-;Hf!ef literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/outlierFilter.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/outlierFilter.o new file mode 100644 index 0000000000000000000000000000000000000000..4027af9286a3fb491bb98c413a71727e14af63cd GIT binary patch literal 3648 zcmcJRO>7%g5P)aBPH>wDIi-ct7JEY-l2*jB14s@+bmKHhkqo7YDMcVT&SqU(wX@E8 z(;pR7M+B*d9$L`@;nE<eXnN`eQ45S(xD?b%<pAx0g9}Jhh(l43pb{a>?7o-0Z0r+a zqTQMKcHYdqx9_cUVjwZ-ktE<E!Kbj|aSEWe2)1pi&<ZUepH{m)<#@N$s#a%WN&vR0 z)v?&)0Xc-eFBDLaX};}&xZe{59|Zl%_CW2{xh+@Z)b~L}{%-Mjb$(HXGj}^Z1)r(} zC?CwkyFHk%iE_l+0}|%cC^wXc&-*$8l(!GL=9h!*tx_<ebOcTTB=2^{3ya6Ux<I)l zzY<WqYIUIn?k~vFMQr)(I?PXebiG<7f5#5yKj`=h`o!T;M>heS_Tn`M>irL~_B38) zfU2aZRZmE*_?7lRlNXXHfXP8G?0XS=XbwSzo`C}2rhG7|U76m}j?Z>^A=>xPQWD3X zk-TbU7s!V$dLVgKE)PpSsLUWgu@NTU_ClqG{5;mw-hAubg%<Tb&Fh1#_Bqw7y?SoT zbSqT(JX0aNc3b}MrR1HZrAKZoE+suawL(1=(2is6pJZvL2W$L-&!yKc3@bPf%8Pj_ z;+oO>_)#ivz<zeDyq_=T!Pg$3ceF4f%`eDs@ej;L>ohkzJ6xXs*p#3%Fxu>_$2-_N z_@OO02b0&)z9YlV(PpTOdDIHkO~J-PU*kH7WBI(!dZZT11C@o5zWK%DU)t{x*KuD^ zh3Gdpmm2o=8_ofm%ELVGujHfLxPJY4M<;fXet&k>*2ry*NF{DeS^1o9X2>QPo6-*H zR)py&(>+W-#q`sV*0h9v7(h48-88Ob8O4;4Y?@#lX|BTv{onk726Y?pa)Wpn>hFJ6 z=^A?J6(wmHc`cjHO(+?|RIIG7^mP|aBa_RcWop@+rEAudsVlwVp6;GVv^N~>QM%G* zp&P9T9ya9Rs6tPok)CH76?8a#gS_zjQoSg-?iUI`#=m+ZV<xw>*?_976&dj4yJVy7 zH{xsSI`M1k(q@%}et1L&<J{-EmvNt6pVq{YeT=udIJt72-R1PNcGsotJS+S*%je|b zRaf97nj3`me~vvm!??=)Q*3E3q3>r*RG&29pEclD8}M7m+l2Stg+9s8cu}7>Ss#3z z{$#wy_(v2>!p`zwE^p~(ScA|}2#wQmH_Y9+l9is&bSRqo;hZs5a)Mr%7}t*iZhsum zpEpYSZatqq)^AKrAfOM1UbKhdcSFxZDwQ`5mR3F)tLp7f=X2v}OHYm)>5*KanAcbL zv+B8}7fVnyj%1)TX<8Y`q{m7bNDU?S#`_Yfy@P`z1IbjfFP<1kvF_{+N~=>2>m}V< zjd+zr?qJr+;ym?{Bf4I+m*;|g2iS`1=IkX0TyDUxHQ+Y|zKPkS_`ak34-5PUW<P}7 z{?IeOCUAZx2+?~d>BacXj%nZTG5ay(VtfRBl1(nYrvX2}xI6z}jJx~iCy4&VS~+C^ zid_}I1&s4E!uKz6>Yw)-bH($ysRAd)_xZ~Lr@9LB4+xy%`Mb;toZ@*OMS)ZNHs+TF zPVo`upA<O7hnWAKz$re){5gTsTzUVO1WxfP^DhgWuMMGV0;l*r%!hF4Siwq<p|(s% zXSrqKc@10oQ47L&_|gy_E0rK@8st!TG#o>hg7D~umw)WTno%g|6Be)VpR|Ib@l~(d z8<bF`8_JBw(fsb`2Gd(n(>kck=c>!+STRbDvJNjY8D2gcPcZKO1-r)TcHwhT_;}8q zM1z=n{5>|_-LLr0C`S}8>Z^wwLHPLn0wa^xXVZcKWMsSR?_uCJ4HATp=SW4P-ujKw zf}xaIA#!P7@$sAKA<76|6vFpEF%pGM^mWHwzVp6C?Rv#_Y?+Ne$sVppx&beDed^0S gcS_)6|LASwg$Sa!T>R~<KfXo<QQmOW^4&fDUkW0_X8-^I literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/planner.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/planner.o new file mode 100644 index 0000000000000000000000000000000000000000..c2bd6ddde79620add0e19bff4afd404bc8e3a2d0 GIT binary patch literal 3088 zcmbtWQD_ur5T3m~bEmN;8cRgOWiN^5Y`x<WB5m}+KRIipmJ&@0g%&oO%f>ssyN!FR zRjy#5eX3GC5c=RlE%d?oR79{>JV<FN6#Ag0Ej}jE#KS_-UWIPyv7OodH*T+&hqe>` z%s=1EKmW}9Gs~TS<+VdTK>(KoxCPH77X`Sp{@I?{TL$YP2v$P8yO~L$QCwZP0)A+L z2`JVIO>?#PgyIdv=5d9GrO=b+P0?lCui$!c0m@UzMZ^~`u+l>j%1is1X$8Qv+Mu-9 z4W(aSM63nn9k}*G>0tuORxj?yp!B!^WenqTt#D`#V<^sx@=u+T_@l4@#ZCaTQ-Z<H zAeh27FkKz#QCITHf}fQX0R|5E;nX6)I0TvL^Rp<t+!bn-!l8v*A8#jn31*KG_o03m zSb1oa4f@a~?1KTek(psX9DToa_84IPVynLh;46kVetJbXc=&cF2tPw49Qwqv#)tf@ z48d?{RFYPG)0saktDWKlU?q(4)Iz&+Z>><CtBFt)5U)0aSry@Wr3Gq1tR2NH2{3+O zBb>q<#w+b$QcXHLK(Dkj6W?k4ybnqfO{^qgoSkStPdTDZwV9cf7FMejzPd(vO?0tA zW?6e-ND57CV78xn8wG7#{g(g(jr=si?7CC!>3uK{1<$(mbn~N}Dwva-;|a_9s0(Jl zUliM}pYMV}!1_=6z>HiJZd2UK2CN0<;KuLXLH?;86FwMU%l8=ip8OZS-B{@kOBC-m zVVpA7cow<a=hd;m9KB6XoRupHs9i(d0@ga-!J^4XPiSY5mA{F^L*YnoXgIPnv~v$D z8<S9632ccjh+D5OU4ioQ6;|rOURuUk=$2S%8E0VS2s0nxOx(v=xQ}x|v#>%lf%9M` zaPfHv2U)ax>rix8$8eP1AdLCBbu+M53f3;Q9m+H>)v=MeN`loem({s(>sKq>vit2( zJJdeF94ftHmU2nss*VYB)ud4Tjd~E@Wg!rZUPb(A8<=}LV9U}GXC~KS4;{p{BtHK_ zH*$JI%5foZIJ$HM`=9!6Y-sLj8#5oZvs$G$k*yWJwfpcs)evK+_nyKzp2Rs;aE{%X zT|zzD+#r1d^)l**xE@9liG5OJ<n=eCaZSr4Q%X7~O>4Sjq*Q4rI-_gT=?w1lWGZc_ zN#nGxN`tZfXn(wKFxJ;EMHD?7#a(>&Zo*@I5^4J4{d+OuHAq0*4^ON{YO&#$6hOqk zMkJ!AdTO=-y5;Y*2}PgB|3!~lgmoUt+3rHt`VSOf1hFmX=MvX#<NPScKjU(c^S3xY z&t>=C497=#sP0|wa(sg0U-NSxB6n>#WV5Sl;9snPW1}?mvxqq575Cu==}m{hFUakD zIsP`sf9LpPj{m^%AjVDhcleXda=eY>qx{J_IKG?XGj%x3WRzS^)niHMIcp2Dp`28; z>1kQhWz<cjbH`yOttQoX(s@-TbNMABh1w}qmvfqYLe)<?2h+K<;q3B;Hp8*JJdJoh zrB1B^q@8i)<Y`@3bB26eQ!-%a$_ZILqh#cC4*#d|%<9caEjy#D`Mf%1TX;0~0bM<# z>Zq*4olAL2jzCE{yW^T{X!5kKWj(U9%^Qkt$P^C_q^6(qqMk@R22P==uZVVFz1`j< z`4Y-Rggdk2$TvMW&5ld=Ja~%>BLCBad;7GN_Xqjk?6JSh`=dUdR^A7MKj*O@@ZeiL zIK=YjvW7B=+|V7Ka(B9#QDTOA)_~ZQVki)s%;zD7Rm$SSdVTzly@Y2e^`<%>jLR2! z+^*VN8^U(rA`^zoOP}*cy2nBCPxrWQ=YDtSJ4JZ?7xKHhd(p%uvh~s)6v*d)J>Q3C z$!8pwm)!g5`{yP1elO=O;x&T^|0FZ644{_ctk0i*X4l6~j#6|0=~ee4N3>(*Tbof& SHadTa|9;=+HO76NJNOHR`g%S9 literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/pptraj.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/pptraj.o new file mode 100644 index 0000000000000000000000000000000000000000..fd62e0b8bc789a00ca7335ad1004c35c4a7c3d17 GIT binary patch literal 7888 zcmbtYe^69Mp6@p^3=jM@2q+rT?+qXfu7hAuadSBzpwUEY7m?KFE~$lK7z2?J9N1k9 zmC8tP-7IbauC=DhR6=68Vceu*x!GOWV=k=8xw$o!GpV{%uJ*QS98d|mDRag;t&`<G z-}m~#W6az?*Huk-fBM_s{`RN8-*3O+g{?auwMh~)i^P7%=0+yUSWWI+U(>r9OJ`{; zM^$;brt;!+R@dVju3a`zz*C+Wu9a$02UhXSfjs^ME8@M64%gau4cDGSzo&Y*b|c!u z@&=wIGw%WPkIHU-0_}sY0<J7%BN?*FSIQ6Z!>?{oa$Wg+Kwi&}{>iQM$`$-U`4PTc z-pDH<zb$vAGH`yqk}a3<-lG*tj=TvvALg~&A5?PXzvDI9a%K6YRs2oJRk^a1O{>fJ zyXh+5n7)yp(Q*_C`<~sNt7O-#;!U|3%7*j}JZB)Ezb;Ek0BcLr*Yjt#uTYlC<^23W zhH`9mIrll1DIXkjDK6I<{>N7`l(O^+o+7W~ez}xadGh#$-VEi8XBB7iDt=INbGyu< z&-}EAYdI=+=allVbIQ5I?B21Qbv(<(qAZI=$L#f=G3aw-F|RVl?kJjcN6BR)7r=uP z>uFw5?f+g?;pURc25n(BSOt9&_#=Gt7Itnkvt9qg%uJmrOSl9%y=7X|4PDX}HmWe` z`avNlxk|X?VuK8FD)iZKmn84j<@0zI*0`}|Gh^3%3A#zHp0WKdthr%lrx(eruHM1+ z7h-KV6@8iQk5Q|#{pnJ;_VG(UU1?)%po+1<JO^7+ox*l$AFl4ZYPX$cF80YJ+O41a zM-Q>^r)ex)yMq<-Ezte54ED)0EPV9M&)wgT3Hws8J|EQ%SqEcT)y>VL=bM{G3!589 z4?@n5+K6*ip{-{r*C&|$V(+=3l5y<emJ4wY`KWpPl*i58f19aG!Ce)nu#9>sZSSd^ zB7Ul6)##AK>f-j4i<>3wzs~Q}M*S&$|9A>Io8WgT*oV$ZHvMI0X1SAzJFHT9%)an6 zLL}=Cur<%2MX66*8N7x+WnI2e2ESlk?oqeQ1~(V5uS{+woJnd2KhRB_yTOYDU!?m| zq0f4^q;I<WpCZ$CHaJ;i3(A<kwSe8dg}cC>$I>uv=)v7qs+`6W#?)`HNrN8h1Ec$v zfZbZ4-Br;}7F7kOyZ>d_+{X=mZLmRQd0Zm95ic6q?SS1X`>GOlk)N9K*@#saVwn6g z74e_rT2JwOcbTgYzWxwj?sD^$@bfc>l|Oq5`I|DhMr{8B;<^qo_9SvbHhk_!i0|j* zZzF#c@(kB1?n2Biy;Q{Gm^+2K3~N>*E=u25l|#Q!725))+&rJHWMTcuU)Ys+dbaY} z>J9u<l~ZZ#%T|85*r}vKKgDnUu}mdTUaGiX&QPv-iuj8QGnMd9mMXoD48@nTf%oG6 z8DbQ%7?r}3*F2lS_irOHyL_5BzwBp&J+APlGc!_TX2ynUM|Gg4pgK`gQRPVN1Y#Uq zPj~-mmRHjsrn}G1-rr-m3;hmvOOacCX|M<5m_76K*Vylie%bp4##c@_y|F(V`t-ZR z{l+(H(aYO(KRagLZ~S3kI}9v7j@Tz3pu6vp2FaGo&>OR7ohJKfd~0`Q#JKy9=h-;j z9o6ldTEeDRV}J59va=c0>T8;=8@>izD)r%G)HnAe|C(B&O&fc>Ka4p&CQ{+&PF0Jh zXj;_Kphd5FRDJ<5c?x;7*OSjv5m!!?VV+@rE)UM}XV^EnoK2hDeGUJo7`UCu?q)OF zAaO``bWkk7rWb74dM*q1Xwlo5+Fd4l_~deJI^4se#KUy=`?DNOcmK0~e(PEFn1UYj zjKnFOZ@T;Z?78Ob8`0NahCRgfE!=Gua^Nu=8zdX)4#>`_wT|G8jVVF0k1%WdEbL@> zSG6>iXR``E<Yc?vv$6dQG5Pokm3tkmZXxnUCUWLvkv;e`oOKA5^mI5`#()29=J>a8 zUvzJzmw0NxJoPCjsOZbZ$VV8nVwJyLyqYt04L|Z1mA_}p-23|UOkEf<#0~K^SyUaI zTDt}IZbh#6qs|rWPxB;4GKuphAIkGAqC795+9FEXT;4F}*`0T4FXyM9#V5&Kd|u4v z6?0yaH7}F3sHWl_?8F(Ld2QwV_&gi2!xkea+Jk90A90(GcaFHHSjq(d9pImMzl}Q} z-oM=J4359RqHlpK2i6SXPKlTJuUT{=HQP(vEC7Dlo~_@b?o+_bmSm~_3f7Z9#NUIz z3T`J3FVol4e5~JyT~mGl@`T4PvS=(dN0&3_Uc%h?3tF_{+^e<W{NYgiB#T~s_(@!M z5&!E&4f2`Z@fTV2<Kle&uZWemiwpR_rIqltkEAK@JhDiM!6vesa(n~&RV(s%VOk!4 z8}(z<t2i&sFBJ3CzuNy@uS53o59NIR!C=1flh?h<5$H@iQ>aXwSmKq^JUr}hD5{jE zm}|#VcYA5Ci4))T?p(2kUpuKq^W+lVC_9yYc@3A-*6=l`ae0yQSnp!xa+;U-LTB|6 zr?TypMT#x0kpK8lq2d_yDqp@-qFn2Dd1)`wUj_fZ)?eeDIR1Df-oGQ#yNpF>pPt21 zq*5;C)v&V)Z^)H?BbGggWqRM=#u=K`C5jKW{`H-e$eG&6c6Fgr=~%3ozWL?mM}u;u zn@=8I;U%9AuVW*z!#g8kr!8XSf%&<Rd~mwkh-W?DFb(+vxf(u1er2!GHpvwp&K7ES z#~rM^(ZO~(T(-eOu5c~Ie}hwtR=G}{NI~v%1D7|sIeoK*?X1on)}r(+TB>^ZxA3MK zxr+__27XF;BL=@CJ{p{rUh;1mH!d~uJM~F7%`@D?B;wwbpN(1MH#1fb!k$J~_~_&~ z8_btao?y)0$FM)G4=k<p(i`T7ZhFV!soT8q{w<N%;jNJ>eABu;1)R8#RpT2EJjM2E zBk|N!FN6QhY-1yO9wi>DSv1~X9qC!j1eZphnC?Djymt>EUkm;yU*CSp7P$=$i9ZQE z5{Cz!to$Kx_#*6e=W0jY+CvxJSyG=(b$rrc%RdpunJZ<fkNE6ZYWu|CGxPcw@}Uno z)5_;E#QbOAlHNUo&t*EF2A9iDhrw%);FI*m?8dy=j`bLC$C!B6#t`Ggmnl1mJD@$) zA*RQL&ihkUk;w;$_Yd_PIhl_&xI0>RNar~v64rTkg6GG;^H%Wu=q%4~fameuT6Bnb z?k1ko44%KoMo9k<cqaX^-Nf~l$Q$7LHug04GyL`Uv+s}n=9{19;f<JDYY*-~%s-1t z@7fz^Gr{)_yz$q6mF}JLYf<xi@+Hh&?;}1kPvhN--au^UYwXTu{6@*EVVkbLCVR*C zYSD>qEqdkWTJ-9#=KPS}$vD1CE`Lvpj<-Pux$Meu$h>2b0iW?5ka-F+9gukuGAAJO zYeU8fzUbS9aw_@uAyj&6o6uIF-oQ7-`>>I|E2h>~<2|}C?+rG;k175*<X%HHd6+Dc zg7h8Z#M!4Z+4L7UL;R%dB|av>`&bw`+3q|&g>%h6v(q~cdna)2E3o$}?EU+DGsnlO z@qLcpQRes9cs*or?kk5O^O_c2Z^|&7`C;SxY#dxq;M`aGAOmjKK!(n|6=xd@OM?Yy zZK#t)mBGuTA9X6zI5T~xtM_J>!=D)aW~XXH#cvUogW8393BVaVcx+pB^|w{ew(mTl z*0r^@`kQ?%`_w&cA+@tPpjLX@Lv4FnTG0#nn_D^q{>~qS0_vucb>4NQWt&RM)~Oy} zDCkA6w78h?k}{QM%1YO*hwlHQkWCKu)yy}E*maBVpRqIh{U8uKG$odF9iUz2mqi%b zEc#o8$V!1D=j!EYqtXA`88S&iDb&aJ<Hf)wi@Yk<8S?krS)$9&;k`nh8oPdD769E% zs7tX!yRh3Mrnd-uNZ_i#za#K5ftL&X`vTV;1AUK}ZxMK@;6cTh$`4R!-x`4z=qO{) z3p^(9H3B~*aF;mR=K}8&_)US6-BgaFy7b=sKd)j)`)Y#fm&Np30*?vYysr^co}3-U zJnsecNl#edru=^hJeD9oE^sv!9TZvc^FQc+lb!UhGSXiv>*Dy=jZs_zuSvl31l}%i zic2c%1wJ6~ItpBrO5oqL@3tiP&LsFQq5q~4AWXxUN`t^l7aC(TF1iFhM1g~H$7tA~ zi7z&Q34ycr_Rf&+*%Ci1=wj_{tp_&N?`wND5ZbE`e&}nh?>g`tD`;YSeEtp{D{rdr z47Tgt)|Pz%Ur6tE_<gMbqt_V<bo!e+TY|>8G4NbVzz_-r_Ov1=>0(f=w@qShy*`5S z=K`TN77PUa?FUTAvJV92wxU6E%N|1^4HCA7?(!y6Nzm6-@ALZut@XZkq{%LvsIg-Y zqtn+1=%D(>bHkQ>09%?^OGo`2Xh6ghwxd<7V}Gb~5A(M{RY%LdJ*>SY;1B$$r6XWW z&mY!@0zV9dIs!0iR;<0%x37MEXLEg9Natey#71)h*HW+Fi*a$K!p|~sufp~8iE@Ew zC*V0E-d6&*`elIy7p|e}d0F5OK%Sl*vkWJ}N0Z<l5$~i&f8d0oE(>nm_ec_aC<*>< z68r-TZr#@*@&?&MA8=-ICBbu(;1vQVKCODrSmdod-?ZRnuA#l}B*B@;V`QgQ-X(C_ z*NT@5ocuwgYW-*x0w;g4;x!iiR(_te;JGF_Xd9B?XDm4VNHxo768xhi_`AZ16YW1I z@I?D31)k`i_bj;eT#huuGLpBR%VWW<eqL_Dt@1TV@F5GHZ<2s^%z_tK@Q*C`Dhqzk zf?M@GE%HCvKM!AEEKcODLEwqJwF;c{SosNCaQe0~%MlCyfC-{~#e(Nq@Q;$<!{VJv zwDT>2C)znG@I*T=S#YbJ|7pRkc1~FEr4~DHB*DK<g5OJmXNh-~?6mSwo&?Vl$&Tc+ zE%sC-!Jkfo9}_s`0jnNX(s3Zz>1#yW88X^tvlj}q`bs(jU7f6?$=B&)C5;^&tR&QC z4E$}uU|?UT#isvHSH)tOcHbAV28>FtHECjO&6PAycS!k4L$#Kh;;=a)Z&Es;eMH#n zzn4h9P~hTOB1kVEB<ySAq{CX)U_d$(*MBJ1_gaO8tQ9K5fOLxIcy`KMug)Sy$F$#s z>30LIFEs(tPKy1XO2AF~t!?7ov}C&=`ldJ-?Mtp??r(nAQW{D;J0Mme9-Xu1Mg*cH W3|R)SZ(1*lWLl-Kn){Qu{(k{r5>l=J literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/pptraj_compressed.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/pptraj_compressed.o new file mode 100644 index 0000000000000000000000000000000000000000..5948fab43d8341736425fe9204614cf99909fcb5 GIT binary patch literal 3296 zcmbVOUu;uV82|3QWrKA=*aj>@F1H&<hpuiD<Ay}e%D<TqQJ9GdCf)7r9j)osdfUmy zNH#JfCd5FM#9)k0d4SG@5CSn(nqWj@<i%{!=dNHfBM;~{p^;L*@Alm7+HEhK<n)~L zJHPM$cWyegXa8PN5WpG&d=2v_3k6Ur=J(9pGH^l#NC0OvfJA=qdNMCT;*KPYX&wI7 zX(!||^^jJWBKsY%+PeX&d=7Z~4-q<J4tQ;H1QIcMXySL|$0{K45mcYrs7Sw#I9S_z zn^>#1q4tmlWzHed@u#)}sx_#Swc0xQ{C>DT`KZu|E}YFs)nn66mdg*`ym&+M{Wgud zNbh2Iq?=||g0b%;xLOaaZF41YhsT2ss5(;Vo#?LFJrOuwcBtc1XxMv3XsBP#+8WTG zJ(ZAC(H|GAaJqItRXf1I2?4fYp3b;1cBLcOTHkS`wXUPP)zuMb1(2KoB2K{x?xBfM zfK%ij+47;RkHG`q4V<W#aLYGZ^Ml`-d7M5ZBx^21VjBI;NHt@#)sUOT_)e@E9-mqV zc{9fEA)!{W+^s_4V+np5&uVOdxVKkN{oQ{0;=xgorTuW^GdFCJ+rckqUtlR$tzWLg z^W+wmb1}cHUV`*#lo#6-Ir}0@O`^T779lZO#?tB~mVV#5+sW^);9W)W?gZYQKX>ln zNa})--DSy&2|wx|Z7Fj4ku!a$Jvm#=a#QPAK0o+_St~2%{NOicyeG<r$0_ES^YbxN zjM_?;6EQa2pUGlelNg@^Se|OX3uE(ReF6$3bgZWrYvhGxPA~S07vuHTYO)t&%svfi ze<f?vv7SqEo<&X#a#sDHLwR$d9?I3^bI94i+O%4<Sp~VFt&l3}lT4coxlkLB0lAsO zkp6(jo*(>iF6R8;H8WlTSeoLc`igFro;@rk@2`j4eQEjF)D}n23Vb&%cb(j%C~_U{ z@0LSn7uLG(3M6K33yFU;A<-qmwI=~;C{OBEmd;3P$EY9NZnqrV3h6y)pZcA0M)~ri z&q2gUPsRaPRq79vBRfH?HQAXmxogH;r~|Mknp`fqB46lK+Un-+$e#XTdt>J0%gNcp z-ejgsOm?lMc-oWM(;dld`GLmlN+EfBgr&Xi%^1ffIr9}uO>NoT1MYe`(*mh%`4f$q z5lClF?n8ON*y$bLGV|m|zq-&buN!-^P*`^qeYX2bex?z(-ivte!Z>|<D4*3Zd~gQe zMe)7B*hYYq_z;o;zBL{7e1Wm!H>-x;N=y`;^j`jbRQTBJ`$FLwV6SzFnoO}|u-^pi zF{o9|nvRx1n)=x4Vax-3a*jr7CkRqG?Ax_#yW-yW%IivJBofwwYN%J~ju=Wjs4MM_ zQ6thF3ggbuf}yys#rq6hY4fx+wlp=jd74`kw`%k>;;yNofpAZ=LO0D#Ezgss#Rq<a zzyW_17Q2;zZWj)TzS@fn2{o0DH72l7Pc7o2P5(tMxSivd`S~ng-{APGT-6lEM>x*J zB5;@Ev`Dbbb}DW^H<yJt!4i}eNw(i2e<A)Qas(US9=QbNHVwsX3YS$2P=K3D;6Ec? zg%+B4s`vA_?<~Q;$N9tDk>hwaM>HBY)VF+Eq$g_Vv6vq4Xt1dtG&QXCh1Iz3i$=l& zy^)@f8b*@d-5t_GdT%@iQPqg)zM!rKbi)_v_Gx{Fffv4LNY`{Qe~*TcF|XOz7Y&fc zIVNh}7Fe8W=to1n0oW7(Ez%n|B4P9+gl2vI0bhI|iUv^FuOAEP2KbNZMr3g{`a5da zq;3oNihJ^|)UR+v4Osc$Yc=Mx(uVQ0!I~1hpL5nDZm*x!m!<f_CG=aZzCb^(E9qHn z^XE<8&!u>f<K(~XFBQZ&E|=i%^8O(`)i(VzOW@#%4fMoSKdy13xCX7Ap@&sZT<?#A z2kWeY#~+J<$B59uqs8K_)&V@&6g}81HiM73RZtFHx4pEYB34}Bp;b73w%3TD^*D*b zaN5V^<;9ai%5l(<wj2ifKGApzC*eF@1es&U;-3(cYjJ3O1}Eu!T=`~{CHqx4?Spaq zmcQ1Wb+*=*@Pg!ddssB+;PNHun~UEf?&b1L7Qom2T>fwgPPS;+*HYVbf04^S;KUV( qQSB_ht^5;SnmdGGlz(C?EJFn1C^?#MYBBj=NHLBB#bxfdRQ^BE!j(t> literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/tdoaEngine.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/tdoaEngine.o new file mode 100644 index 0000000000000000000000000000000000000000..aa5fadb61d4970d9a2d82005128b31436be69926 GIT binary patch literal 4312 zcmbVPeQZ<L6+eF0NlZe4@|BRJwppVB(PAapkZ>!FXIzpMP(g{Sc3~=Z%mcf2{K)f* zl#xG@01eVIX+-poerav0N~_&TwChlLTB&G*)~eF93T;T0Dr6f(qpJM_1)8|vdgr{4 zaBb{=dZXui@9&<E-#Pc(`(DO(@9Pn4Hn5rvK7{)-3k7&?)%~%k4@Ibl6;K%aC{<uE zGv5LQhZuA&^xIMk4AQq5Yrk_)NZnyV`UhrfN0pc0%+!@E+t?lyV4CK^RpQLZwdQ;z z*IZD)*si(WYxFMk`%-rf?n=$Kh=sz~<##TzLswmH_CM<>jD4*8TWEkh`5`;5R!}kk zfnZM6zzz=wbHCOW8pM2I>{DGoSU+Om_1jBuvRN2=->`?gZ=<~ov!xgCA?`mQ_dATG z7sD*|VJoc7$Ly(Bu_vEPy6if`KZ9HLCh^BCa<KR>hW)90?8#JN>_0k(>nNXPP3ie9 zwL>??#lPp+M)b8o*QdN?m|+WiL8lcHZcAW(OV3a>n{^XYS4i(}vL<yxsGD9wzPWzL zH!)#`Y}n@f-kso%1s{O`$xU{TXqz!Vlik}jT5oa(o&R<~VB(7r&1Hw-OE`8pV0bfO z+SHYk|D3u~oCEE3+^-B{Gg*uw$6C`T1vZ`84|$7os9w}EbE1|#4VnvJxT6*VHkepD zz@V@AE@&+<(U+YDEjuU7WcNb824MYI9X$Mc9n6d~i0!dM;1$2<J;Y!*BmC~TyI2fl z*`{{Oeh}b1*<UCY8*``8kG{4(eSNQ(w{iujlQ}5no9xKtT~TwP-RMunzzHULGbook z2YSr8bE0+#bE5OTTMXop*AjC48f|B$QO^!tv#TI*H@Q1Sxt~S+Wvo+*pK@XU;92jB zn3pNc59Q;eP^0JKgiwn)T9>An?_!*%Fwgc68ok6Xi22DP|4pcyISblO%+YsPE8n1P zK+KD|0I)Ueq+Hx92HIAC(oDHHb;H(jN@$xtwNjj!I)=JJ&+!S2Da&fxb7w{EI%~li zTA#j&dB2C_8@;fckDHjM8@*yagnr2PP4qR{i8fF!``Vgq#4G#Sfo)VDHa*|9%lSqh z|M>O^DA4(s92n6uxaWV&4HWd+88B*Rk%2CsWsUmT&gu2tsAG#*hh+ap#H>ABq1Sk8 z`l`^p_o~pSpa1g$?EPFA{0rVUXLkMSY~L^D{;CwmSEgnWBcE;%3%g*8GrM2R7snq; zZGG{#uHtpj99s5y$5)}}9V>!P$EFvY4&R`2e!8{8s)boRH`e}r`-E6%!PxIn?LE2+ z<Hx!|+Y}$w66t(~>lyT669M<xJkxZi6tJfH5x*d68$iId)->f{_Hm<@aR2pq@xIV= z@Ybh(Z`cWI2?x9<#zBZp2zaKbXLvW9WZvv)<|SW~*9P)#*m;%bdFv<SVfu##p9bQf zlkPKEgp1H%(^ezTxBun$z5x&mA-6Yx#ol?$cF||@boe$q9dFw%(q0p9xV+ozLKz>{ z)DmK}pEY<E?f78a>+zwsXY|_pKIrxPA9ru<efk-9K$hd-NGO_cACVQe8j;+-j$?{^ zBpSz&5{^VwDXfktlH2R)?&$99@_M?u-CIM-PzR1Ww{0Wb)8(d>uFmf5hLdW)^sceP ztzxBhR`E>)!0@k9V`!<o8Lut!@?c|tH&I!`gNW@xoKOa})Ri<!;#!X9VRQ9S?AMe? z8WXw@D&f6|lbvIx&OWmrt|I?uQ~r`E_njH~xhnFPtKeT%!I!Gwk6<b*@%L82_f)|n zRq&}QIG*W>e$Q9IzpR3Pk2vM|J#&j!Vw`$Y56hw5iKEek<OxIDD6}1h`_NN~sH#u< zRaprgm1rIf#iPe16Ah`!Wf{XtucZ1C;fSpG)zKbVIS>lRB=vwIhoxjPnmEc^Ls7pX zg;Z%-fpcxD82UZYxGE`<LCxfX+I^#e=#WK4Cx~Fc0K;)P9P`VHf`>LLCk%4_P&_;m zM~~$+N`*}iP|?OS#|}Se;Hh$I{!)u&{`#aLS(W;w;ir{-(PT-ADFO^?|B;?}^k}4f zNmr?8tYR*V#2%27xNUNxT6U=pwi?v{Em$Y@=9s!29Nxg;6CC~!hu`M#)f{eJ6=a`3 zM<ULt5pLW;#(W=#(}$<k@B>S4B)`rAv45GvtqY!(FL3w<P96kfLUuNCIDVt+jqpYe z$M@MX&d2*V4sYV*-R4zYZvPC2^L8$9IB(}m4(IvcH~TUlK3=<dAC~iP;_yuz&o&O{ z^Rt7)`F(uS#Mfbd__xCEP25?A|B18H%=x{<;d~zc%i+BI5{L8gI?Vfw;^pxGhx2h= zF!5%T=l-<=@Ff2*q=p8uR~4g=SR+M>hdin@s)7fPeh55+$s~9bnI@iaQr!Wbusk#* zB~&iJpE-1+9#SjGEtwMO2ir#`e`8j9mI!OXhf*ct!?!io;Wg`~4j0Lf!xXY=?lBWL z#mrTJdu4vD1+u}nU*d#p{#^Yo)FqqznaAmJLM*;IhCkNa>VJb6>33QJX74bI^<Wup z@#lN<NS8=PO#L^_Me?@-AIq<mKf=mmCqoWez*bXc-12Lz8h2nN{WWH>()SYI%Ju&b D&m>*X literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/tdoaEngineInstance.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/tdoaEngineInstance.o new file mode 100644 index 0000000000000000000000000000000000000000..da59c662603facd30a8e1c0c42df30bed72eb4d2 GIT binary patch literal 16752 zcmeI4J8Tm{5Qf*7M|dh}5QyfGkZ=S!#TJhwfN*5xB>{;bNRbe7E@vmUWc#AKjbti9 zM@fT}G6hA-P?0ia%9NCpDMObIW^QNV&Dqza0%=x?clO_ZcGlne>}vCI;>F~dOh$3b zs2{2`VpXZbXPvkhhedTwT~)dgcoVIadaG*Y8^Ov<1w!a&buElzoN0R6uZ=fW0%KE= z4pz%na-?6kaVpXik&gTMdK1=+^klHssz6`z&HQxT%)hKhky3uFDy4&EoR0Ss2l65W zgn$qb0zyCt2mv7=1cZPP5CTF#2nYcoAOwVf5D)@FKnMr{As_^VfDjM@LO=)z0U;m+ zgn$qb0zyCt2mv7=1cZPP5CTF#2nYcoAOwVf5D)_Y1c6T}yO{b<^b0BbJd>iQ`PWnY zX?$`i{xrQW#h+GJO_fSxPHyVeTW3B98h*{Ix18l5babuij1R4b!E(I;QRvs|y6Wq- zu<DGug`vW5e$>quoSYXnhaegr97NsCJ2;acE<8-x2+4Sd@vQp&r<W_+^M<2RS=F0% z7G`?2EL2Fg>#@+SqnuUel6GbM-MaCgPw{u_H^G@v9o?}mab{KbshPUn`n`Cajvimi zq+MjyrLO%v2W7x|Ux$1yox7bgtw?(<zv}wxPDPc=a5XftuYQ)xt6u0ePiUR&H`>#1 z50rO=S5<9V4(*8bX&UD&y&vNB2SymNbX;eS#zjj<{}%aqp4VR>ANQ!E-=X(iv(~}& z7iqj|>FA#(|GK54pYuOkI{Mq>->`J_^SYasj{bex|F)&0zfI#EOGp0^`S&ax{p&Q| zw{-Mt+RrabM?dfTz|zsbN&X{CNB<WZ^CQVTzmdP6KF7>|g#3Mpb$A&kp<``qInya# zf1B3l^?3ao<SQop-^o8`>9~Jhcfr!J<{tTLmX3a|r`+g6Q+rF$>(KNyj&!xHm0R(& zr`#pD<m`q44$zr*N0jUPO(Rzuo(oTt+j&~Ri(>phosj*Y*{rrS?dJ5|El9;9>3q|e zwTh<edZpt#)^9_ETJjsUc<eYCB=hgWG@kuw^Y240u33OTyA^5h)fOSfTG)6WPbf~- z{~5dBo;;m94UhAAJe`ui_sBRLE<_1jpYux);IB)O1?soPOwdn1VV7ZuXT<sZxqc5C zmPqdZ;4z5M+NL{x<$M+vAm~+p=c#e*k`e1;F6VQ7y#J5&hvCm|iz8<A&K4nN9CqL9 wS9+K7H^_Jea`8D#*1rf^^1Xwk7Kq<04y?v?SsH+#SALuRKSG<0)F<=*0=fLam;e9( literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/tdoaStats.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/tdoaStats.o new file mode 100644 index 0000000000000000000000000000000000000000..56bcff0ed8529d7e84039d2dd68ab78db6e546bd GIT binary patch literal 1584 zcmbtUL2DC16n?W)ZF&%_dJqd{302e5EJ;9ci%4qJA`}lv3xbEbNw!UBk`0>?S}HX9 z3oPW|F?cdPd6QfuNa<M$dY1lzN_+4U^u1)(Y=?~pePMX-ecw0V+hK<6JY0IDF$P{R z_z1(!LjjKYuuk>M6ih$}dfT7cJr29tt;XR=mbFhgn`O|*oN(A{9*$3<v>CzvJHNaq zW?ARey+&roV4d6nH**JLCh^bT!7kzb`iKwf`)pVr`Rdo&5RVM>C)tH|Z~OCm^tck% z`B!gg(S^<`u#KDs%Ubt=$-8ND2egeAP|wZqDRjaqZ7V#@I@&(+`vbl~{66xMi+mZM zWOJyAvQC$;euKqydR~t%K3UP19jBZxTBWMK=D4~j+WJDQ<~nPoGFEQBSQ2(#yl`#Z zG?KAoJYgD%q#m{0N(`&`%nad1LMJ8>Pu|88{3Yma#^A@VAPEn=IRK8opy24F#)Uo* z^a9A|oGOQlh+Oi`ZA!&;%*3g21A!p?F5=|Vk{h1N45HvzSz(E~k%#HcVf(mR5>T-# zbz4B4_;gidEMYG>>+81LXa8(nsTGjvJL=MR3Xd4_W?)YF@ChHjGy?a&k9_?4!U%nB z1paaa{zl^06n`-4TNPpDFbj8(i(cj0Wy=uurT_!aYk`rg*TKj;m5N;z((iwhjt2BP z&MQVK+5c2<^{%Ior&pI!bjR8N=t`XYX^wYCS0#Q^;_8dOL*jr?;W^Zh=fCbx;9l~K z<MM|$|Ct}e+MDms@~CH&Z>1n4^Ek4!)brC@Q@@>zTGG^euY^%}a|ay&{UHbK{~*D6 JPbjmx|2GMascZlM literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/tdoaStorage.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/tdoaStorage.o new file mode 100644 index 0000000000000000000000000000000000000000..41a4be52ab50c9e87468ca9ce111a0dad3ecc8d3 GIT binary patch literal 3752 zcmbtWT}%{L6h6DNKhR<XG}?d(14Tqrwm`LEjSmBhQWB~b*2Kgnur7nF%kIMNv_a9Z zDr(HWNNUogFJK$1_|zwrq?XmR#)dR$FeSc;_?u`STB~-`;P#xEb72{mHfb*z=FWG{ z`OZ1ty?15@x3+AvS}Y)j1unzFlRyEw^A_fcK2;zWa=?1}#FPc%tq83wk)>be2EHAe zlVI3}m;*06#0&T4!1%K^%h-Espzsd~F5boK`5x=ob4j|0v@6%iiaQM}f}?iuuCpoQ zrSh`jG+2W-<e{P=8x%CiCyPcD=#wqrl|gY&*r2B4ReIC8e8W!uWG_vpy<~e?45?8o zcrUFveCr46+Q~~#58ax!+9#)fKYYs?h);cPU6r7kXQb5^vF<Z6&YzWmJHG$@I>7m5 zE2N&a)sH>j(=hh3SV_$de19P+wNFnY-wkWU<h0J`n0%T}uRfdMEBr_YaoxvW0W~5G zO0oar012|iv5z>w#-rGKJ6M7<0Nx?$1ME+z52|AjAVqmQ`A%`|0DZrr4ief)V?XL+ zN3Ovw(1+X`?Z~(GW_cay7XP{7ARy<HS7~n?a}yWw(p}U?e14_mqY&yve7Ih%WOE=V zaXds$2d>E-kb<YMMhEg&++16C4s9ctllVt5PXcp{X2}7dqyS??PW?Gg(fgu2`g4xy zId1aD{EOm8VOTs{i9bgf_tYulfPJ85!5*wr^w}`fR3&3iN~3c1ZGiEzA*hn`;HrqX zaJ)R^tSW1St8yL8=c4*-Y(HwVjKys*ek>02z0B8-^@#oNM1NXm((-}q9R3=0Jl6rk zcW{l9w8o?x?$vr;W2)oGp~26}ljVu~dA5WFd!gEo->x5@z?fY0JMvgbQ4jUF4~~>K zxqYxu!`#4k`gyz84#Ts4y^b>_Yan`eImYCVd@(n0UEjM@D_w7JeSWTy&Sx&>bdpA; z&S6@2s<i|6gCien(QCH{AMshdAfM3B;sYsX!&zMO8LZuzT$gBC=1j;3py00Tbl)p? zx@R9lYUZ{@*Yc5M+wcO<3gt)s6lvqcoJrK@2JRoi?U-u<oWUPaBihd@?qR!4ac||l zOm&oi<H<G5S&r){)(?Gky{*Xkm24UA#8^N2j<DVhsCWB<-cuA;k2RMi%MxGaS%uzH zp54m$AnUDEF6_r#=I8TPNbj^9tX(d(7<FSlS|<hdq8_Nu39#Y2>sS$;&6D!+qCw1m zUvlbtB{8=nS&^t%=14$&Nx?PQ;=W#q=X|%((?dzx@NYh1E$KeX?-$y09(=bbSWg_! zY@@8WNrO?;vjH`32WkGjLK;Am$Fo_kY}&p{_C_K-{%&6&EO$ksvevE2^;NymNLQc- zXHkE5KvVtNCs9>)yK1Xyt83h@np(Ni7Y$Y6ta|-=!d*2oS!$|lH^Dy+`nK5Mw{$iq zDeIR9K*GOlLqaC=Sgr%vzF@>-H@ib2B83@w@q46?O8lSC^UT}3_(1-`X5&;JGLGLU zeY6-iP#N!K`~$|1F`i`nW5&-jE?W&i)N_ULY7_nw<GBCyA^c|<-)X{MFy3LpS705~ zSFZ`LV?56I79$PpVm!(CTZ~5;pE2R57#B+^>O7CQ(2^<i8|k9!%uC<H#u>)rjMF;N z_>1vx7(ZmdunOxSo@(AIEsSquJkGe#e+T0;jGtlu{lcHO5dKgwhSnMJwP}&4Z=dS& zLwP@B0L|fm7Vz~14yq7RLorp$G&ZT4C#w21wLa|cjzm4$qENIhg|`G^+Kw*6+T0m4 zakAB~1wLiw*L|8hO+l^w-atq-f!=Ijo7%TMYI1Dx#k5_$o!Cki7Ee#aAM`|`QGAI6 zB4L)w#9%bDGZI6+BH>J9o6uniBUawu=+k_eF{JF`tl(e#yfwTp5LVI86xOPSBARNb zk*(8AduAwBxs(Z$7$%*MRwpwMt)$tGu5CSmecg*p$hnlMImW9$FDL#IH%1Yj12HEg zX~0ly!gKhXkpF7-q1$Q3$zPml-Rz1T2x-2(;EHKc<K8W1QMJeC($szpT(}8*;MyCD zfy*BWh19T?!To=xG6rKw;4qOW{CvgqYB#@AiqVgbwD9LJxcR0r>tKNRDUZ-lXi&j8 z%fsFPf12_N194=IckqEY|7&~=#u8^WUYSGW-;)XAT;$KZ<16g7v6}^b%tj}A&}HsF j7cq0~M5d4d$4L{p$ZJ>u3UHDwzLGx#n}s9a&GCN&R(>rV literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/uart.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/uart.o index 2e96d794b41454348d431df4d5775bb1b4035d61..90412596972e866cbc49a2fa1290d91f25e100d2 100644 GIT binary patch delta 537 zcmdlWH$h>72Ga!Ijao*`rVp7JRxvOzOaS7E2iX{Y0_iCrtjN$1RLtb?vw@-OlERba zpN<0gEgW5!RDf*8$+gVJJn{<6S7CVa2If!3Ky5(4%N3rOS(2HTu27m+l9{96lbKgq zp-^0sSX5H1kd&Vfkt$Ho)6?VSn!JFeV)9&G_RTV^DNKwelN;HCCof?a;f!NsU=U(p zWSFq|CVM=iVmZ*n`1H)=_{_Y_5{As8!uX8Dyp){OB8Zg?B9kX_if>NfOkk=P2I^!3 z3QItxRG1+QQ8aNKsJJvxTokGnL>VB7%OQzdK*cSA>ba4`L!jayds!G5Cg11glq`UX z$w9;zUO?6Fnas!|Zg>PL3vv-q2OLO1IZ%_};tG>Jd5$v{Ocvxd=RCm)5w4gV$ZO8D zfn_oytJvfPyc&!fCZFWB=iC4_!fmo3pE={V$)0@nToJ5Llb9z@;xprn;DB(mCST+; P=XBtO@H{6^<dp{ihvZ?H delta 296 zcmbQBut9Eu2Ga(fjao*`ii!*kLB&iCKbsi3E-5`({^=-?e}IkQXA4KyB^4mwaq>iF z<H;A8KTZD5QntB(HG_#!Ve(D(U{)apMuvjTo*eOvf|*5y@fnGEDLJV{3?LvfS&&P7 z^8?NVCP7O^1_o}hAcSz3ypcy-GKLw#lLN}K0GThKD&|an2$Wp{l@*1`LM0h~fMgjN zCTsE@XAGG9k=LBlgA*brG1-vMoM{5f<Um%j$qjrOj1wlW<g@3T05Tg01SfywGiO{l nS(D$Mi-8p)_JV105x*Jd3w8)MX7WaUbIt@F2+wnJA)h<|NyJ24 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/usddeck.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/usddeck.o new file mode 100644 index 0000000000000000000000000000000000000000..d9b66723802e7198793a63fe5a6ee8f930ae9eeb GIT binary patch literal 23936 zcmb_^4|J5*b?2KIfn~rB7#Yhzst=4)BHOZTge^JgVT3^77y_2Yf%TtiMl%B%^k;^d z5tb~s3<mGIi_=Apw()6vifoe{P~8*u7&a(%YPlwjxAtir+s$E5+;)&Tts8q2vf#uD zDB9nB-@Ve+hrXsg+joxUd++z|``!EQyYJ8UW?=97O^v}oz(@+1@0h8QpvDxoP36Nj z8#d+U2Fe`@%qldYP47sk<wv$0m@1F=y?SgsWcq;*jQ72E)I1*k8uDcoPU!FGkL0Ih z!o4CFFoh<nGbTKSzdC6X0v0!>KRG`<d@dBI45GXi<+C9(R1B3=u60cR5mPcZG2aYR z8<8LH`<}I9^i|02b=w#BnmWf6-bvJkhrd~3797A|673STw(UUi)o|T--|I)IUt;fg z-(MU<Uk_2AF3dG!3zwSf9N4(b+H36`KnGV}m>V7&@B7Q6WCOf+-9JoBd|hM0=d~{h zTP`#QjxB_aT+sCAmYe>Iwr>lEK3QnSK0%-1o9m94>*tP!t{)OxM?+;pXG05zE;QF4 zD+2#yA?bhJ>K9$~B>Tm7*fxN_L*zs9a|q)|{b;~gE`-mEp@o$sLr=nIvS0Iw&C%r> z>k7uyh&=g^d`7yKVXWLSH3KB4Wv1E3KFGrd1;`b_NB+QgHAR<~)=@vnzY=rcwlPNa z$PZ9FP=4Q>0OH3Ce1J09P<W!WpKMr;y8YL>b%Q~(+G`)_qIMdeg;-gEzYzX{cUnD@ zI=wdOcGO?to5_AXKF~>iB3?U3#`|7z;}+xo!3D$|{Bi+(K~Nnkkd1`}{Tvr|{K;m6 z{!kso2gQVmF1B_G_vjjmvHD|yXn2_7WSI%h4MffGc;9L3&*`?qS25S8A5Bc$fV#2Z zeA8P|W_kl9fnyb6ciu}M0_ZE%5l;1b?vPAiKIV8?xYse}KB|*>N&UJQ3Jg)-s6P*U z(OgG;d3Cwd{#3|Bx`U?XEMokdv(5d5*`|M%bMrysyQwT(8@(2>YfN4Ax^QnI7#@qG zTrlQfyu|eHHRhxE`~!a+zt)VcF|$6}_v?vB>mt%$XgV1T&h1`gddU|uU)*>?ta~u& z-+145-T7nfg{=<-kNpC6Uyt#489x7IJalY3)&#OWmVL0Uc)J;Ujn)I=duZ*kU&b2{ zw|`~*-1<V}Fy`_z(QE6+)?)2xePK4OSp(4>n|on@O>|eoSlE~ogneyJxc586|H9(_ zV(5k;!g9g#xw%TSU@v_1)qshdM7@no#3y*)83ZrM&7^yOFx<NqJ~;bO!18_YZPQD# zL9E?p<1R+!?WKsNIpMnKEK^gCK9*zM8*48)_VvZ4|3;MSP+kmO3lOhsOz<bPR=hUL zMAn$lPu2zt?}STCgm_+nZ8RstgNyq~FJZ*{;8mu-!Yppz95j&&k3H6N7r12IsaR@u z2X8FAv%jS9&TGp@{`l(giAXV2J``L78$&k^QCs05j(Hf{vG#Sxo`){yNaL`9Pn{#P zhrf%sCEFa-ll+Tp%V=m(Wfb-h_V<vXr?&G6w)01*8x56Lo((O+9^?A{&w)`)==G0c zmpDq`mjjr?Po8faJ`i2fe{;yx7{qfBe5fmHMSQ$!ZfZ}V&kfiQW2cuNTz3BV-d$!w zZ#KZ@eI<c|%WA{DYm8}s9yad}72X-a+8je%n|UvMqxFffT{jDeaasc(f-T;4RN|G^ zJ(_QWm_O0d@R)=7o0x|=YDzweBW7Zlj|t4#eFi#>d2<=;tT(1NQEDIyotVcoC-!;j z#;m^zO;^ls=n96zcK%~sxi5gVK+BBx9XVE*S7@?(5atlgpHE&4+Id59btyON*b?}U z{7Cx}`7!_>kv}Q6!|vMs4%G)xM?OEh!Pqz-MZN?wB!~Tq;>eCic(xmFeD)YXTf4>< z*O;*=;<vbp+7~QmaTR==d9bc9F;Q~?d77Vln?hqWM@eTC^N*e~&j_cv=Gud~Jcs34 zAF7MDF6rO<%$(su6~-UFq%onGG#LNb8_`<WTe)vyVm0ZEl$iV1mYVwqen0%Rub{sR z5jSVCeoyuxU{*(W<!dX>ncV?!3|1P<g@r@0T{X2NNBRwHz6h?hG>1`Fcw&LIb)?d) zE^eT{m_wt$m)ZRV{Y0BWtJ|N}(!zDtXYpYFXgpZg`s<0W(>$#wKehwAJJ9<Gu-3)l z;bJb>Px$B;0=?UT6~9p58?B^1x_+HVo8eFQ2m6a(Fk{rWvJaQ^7yD3dFk^)mT6#$D z6MxxKOB`6ZhYE|$4@cJode?(%AL@$}hnpz&ovTe`RVX|rK5)-?upjICJ&^riO?@wM zEN{SBr2+jmp}EAf3Uv;!!BSJR5cQbYhZf=Q8qB>gVz2mOux=S}Iw!4!><HEa;<=gI z<*>h0n1$_sHrqs;tHNWC{q*s7jahtfNeS7q#QNH`Wyw%E+E^}dTu<#GA832*)S5E0 zyST(ep28ekGtcaHkY6+3>^7GtB5O*_?(kBSOU>?mz|GaJO+Ut*T7xwY{)nt`P-jeJ zknMes>dG<psB^Ay<^L9#oVjN5(a*;xzE1rj-~1H$-d|3fEWq#1oaug94Bw3H4E8Ue zGY4!cTxB8^usJ~eC);+4ziu3QA3Wl(|BXEHiN8A0?zzWuJ?^=q9I?B!lE(T{^Ob)4 zYqTZ5g)#qrfc&LxSIWG`GDZ0IFOV0$3iuH=ME>ko6Ojt|gz~gkEQ7B{$X~FR{8a%z z*P||6>SE+CoK1E=4>?0Vgxp^Pv;If^2guv_K>jrH*3ZblhJ0%t@>gv*M*aC7%4gHz z;eqdB?Lh1=!+fkTf%dbA`+5H|5jl&Pcd&-kU~d`3-v2rHRo0bgiCqiqdhrX$1+c!1 z@Y;es2In=J^JO;1=-q<W8LG$LVfS>>|MK`m&Dn<f-XeU~1HZ^RC2N$lpJ|N}JBpVk zR*$m&@Vxr5X5I&9!&c#rS)aRW=#*`48UD_`hP{b&iyrjl9kC(G>xy0DfYZJ``l1=$ z1kNb0OVrmW)=2785q@cX=1ar0M$!62ytHN|aYmwbH1RF$=h&x6R`k(YOF9WV^lOY4 z&!ej`K6ZRD&u1fVV*>dQ@=v6v#&H5|Y;2(JGV%udL=@|3bl09*TBoDC?y5ZueDqJT z=E0uep*h26z(M=?*MO6)lqY))+u^s)QcRG{nzoSbgFchdndMS$J<f&i+jAkUooVQ? z`vr8Mf8-<kK7i-6auH|Gv!P(+Xed;PGw`9flBM>)sop`1q5Tl;wQD_Xsl8KjY}y__ z-ZyN|zjV&M8++D7(Cnst`&U@UH<y~or{Eg<cA%g3bvhIO0{BUs$=!F_LQ@(1b?Fu} zcIo9n|4FQ~u(|AT@P_uEV4i+}wRJh_>1;>wLgRW4^XxF@aRBcC=e}KEcX%b%r={U% z3XnH#-L=lIEABr0G}hW14ll+#Rwd@f>Ves2!RbY&mU!E7X8gyXsVjyS+jnC*gIk~9 zLhr~wus$c5nt-YKO>#7DblxSNOK4B>bfzah;iCEqypOnNBpR=9ot%N(@e2=o%9Cd# z8Q)O#t~!G=z}`(}_r2H$Nd7d=fKTEqNHIrozrXCoZx|Cg_~XlNtk8Ik_nn-4KPiL% zFNA`2EXbF1KBAZ{U_2;hN3kChPJgp74)mn6mh2@|#y(dW#(4t!QWocnh`i_Q!5k*8 zBF@CbMdL>DgYaRrX;<A~$bF|Sur8{TIU=z?-uI^UJ;l;58*s+p^L3!a<qBVIPT1JG zDcJ9xX%^d<pmp8MF%i-uz8}0iQA6)PWE0u*GS-X%=zigy&AqZ74kAx>P)v@@HYW%d z`4c$TSv%k_l5x-aWkb}S%HJA#sE%ZjKlIJDOY9xOtGn!6?w2!X@V-LRMVzmGfpzU$ z*~N9#?q$3K(zq0UD{OgO|GMuGBd7ys)81fUR}6bn0q=bK7KMlDToA>W<7`{`f3Xe_ z56M#brznr$y>JpkS^V%K^14qX<L7hobpU>r_nE;@CQfJ{(|bb?eCUoz`Ox!-fzVCv zJ7W0a1bpYt&kD@Pr>-@Te}Zi#STjSVX2CGVVHVcX+W3<GyY?@z9HeX3o1d#CeY4(N zQCsomO|@iSae<lCOK1O8@4EZJ{$QbL9duSKF~gWkKQCT&crn=$diPqqa^jtUV&p!W z*EbB6RG8im>=_<s4I10I_MO?TlX3=a#e9LU@viHh-=f!;)qS5a{pH}IcUr>Fa-T-7 zp>@EO`xJapmv5jPXVGZT^wRqYy*KQgW9snNTfEzhdHqRtgb`!3?vw6i&`tdv#CtT& z-N&yoKcsiT1MTtJ!>4eD!TM%xz&i=aon1rkXn~Jz!dW*O3LHEe3Jo2_e!CQH&xV#_ zedKc}os}J@ePkZq<?uee2J6LBb4>*87R3H)*+FNX>5aoqHx_UwfqMkUICG=0`(4D# z<Dt+&TB~rjvUBTSfbECh6ZmVy-&av~E;J4=!&p{qG`l~<8P9<GU93e5OJ4qlb7A&y zE^GQPU7R>c_aCyiBkr(9$$g*uu2xWMfrEOQyV0h~I@$l`Ll?Cnxl!~_d^VGB&yiit zQ}h2E?bDu^E?l}YrnSsXe|wFcli^=Yms^JZVvW7d`PuB@R*d(uRh4!7r`c9MY1`|- z$=-ADAMIcEob(0voYKd2AE1u<bM|f*?*>k50{vlJXn)ZA!Q|aI)sOf6xn0j`Kc#n= zzk`oo#Jcx7&Xw20hj@pnq`hdo@B4Nw<@>=(x=W)t8^jrj*0pVTuZOMyternE(At81 zjQsyI*m4SMIi1s<$9$K0P26Fu<v)TxId2i)2*2M-`y$%oU9(c!jo>|%?&&^Q6#(ZA zlQ^wiB9p@&UEC7JyuP9R6YSgn3=XNIaTVXV{de!}ssF2SR{5VnGk2<wK^wE!yW9U4 z`b04|wYRwU_IMY;y-gYJ>DC^@zE(-~axV^lnC|9v_c-gb*>u)<v@O+<bW&ZZd@9zF zdMwqo(?PA1NXFaekf=>ozBAq3m3Nxg-PRDxCY*=1-1kV8NIcNIZqt?x%<GYBtiN}Y zNLE$dPQ<q-vZ+1EZ0`14Hhz0|E<soo&TuA|kL9~_&hPw=)7aFq<vz0`){#pBhfE~Z znasM@u%1onojb|geEJ^e=A1QUN2({8Xv`*ecPG2zi1L-(;Pd>f;-~G;wro0|bZ+iQ zIBS{1SxKez4htstB)jst&s$zA-x!0Z5)gILnPiu<10_*x>mQA!^3D#pG?(nkrL$yF zy6YaR(bhlE)!vnUw9B!?uEo>vj`U7vPb`~?wPHYS&Q)=rh``D<x2H0WM~Do7ptCaF zohQR{`E)k6GwE8b+r`seJ5oEH*p7TMJ86MmGgn`O+a#NeO^&w9QkCz?yN<MWO_S53 z&H6iI9UbYo)7rgb2Xx<@a9Vrw$(%FUFBM4-G_Tv%bZ=z6%g*f|n&Lzp*s5G6wJp0g zlM^|Vo06)$BbJ|DpHF96q%j)BV_k?IW8h5+AwvO3T&;0ffG6CTX%Ubrena{YoAbXV z{YT6FTXd2P_Lpf1YwEw6UMZbkjXm2GmQKh1wbDMHN-PmGrhhM9n32U8KfP@}^8Zmh zvd(zb`0<+!4Gs4=D>r=k0Vk49cf{LbDJ&>hI`VBvr~bA~HchLGQ=g5urSi#mzB`+A z>Z<O%?at~u>Z<Oz(^(nIcHV|u_2)lNc-0*a)!b2i=W4G7)5{bG*a|16qi!j5MU)6W zb8v^i<V|xe;Egt8t_2=c{PVftXBn5WJa1*(VL6;vZK}a1@r2!?AvsF4$`YQjC1a}j zNpVH^AeT4ta|`3=J@{7`4|5mX)duSY<Hs2n9%>#kc#HHTyO_*?cR|kj0T&OHHn|V8 z2T#JcGJcWq-)H>L0v9;Ss{TOad1&Ub{4<Q>oNm)0#t$=oo`-B6>p97|xyltBVEG?1 zUR~+}w{rbIFuv9P1cGA8O+RBi$^-Q<<E|e>ia|Wa@fVnEO?`LMZ1|UORy$d-P;eIH zVK9pspU=3o`)$U{J@{RWJB)|<`9;Q~Y-%mz>ll9)7lf3gCtDbQj&T%idW7*o#>Ji# z<3|}^$?`eI-}cBKVEhc@r+7T+MW6h0h!0+3&z~?pz&MJNDP)*r62X@YHh(2f7Xtw$ zFLr*1aVg95b;h?cx8PI^O^qVgir&)6vSi-2JX82~slYRYOAl{y?Y|QLd&@J0JKV4y zT@8Ro%C(9xWMuYCfiC}*I7x);YBnWHIai)mx#{VgwPy<NQPm+cUzOaf%X20EGs`oD zZ&WQq_7z6~$htiA>N7o!Tb?OAs;WcwDog>$&cQsG(mGXltq*>q4}O~u-r$4Z?}PuY z55CI>f7}P(?}I<>gVUF?Gx-7Esn3Z2sSo~|5B{zX{$n5fpM7wAVKSpVxJRB5zs3j0 z-4LQGV9xWp!^^r^$@qL;c*-~==yHnWs~HzxH8UP&{3y%Efs4#kR2j3|2Y=EBr;GHN zcwY3u|A!C$iVyxbz^Pw@y#FQGSlkm@d_FH(;-6po@ZgScMmrbz;J5hTwLbV7AH2~A z-{yn2``}q0{7E1D4}I`I^1<;tMC;G!XIux%%KL(k{3({tc;rv|$p3)l3oI|=b=pV% zJ(eHz$kXNJOz}3#@*^xS^Wq<U<o^%w<%p{y%gfF;#ysa4uf}>!X#viCGwHq22X}x| z+&X-26o1~uc(n(=m+`O%e~|I5jMuv6m<;fl>?!!*2Yhh)0%j(jV?OwCAN+eh`1gJA zw|wwXAN;32_?QpA2<Hv*f0)n7;{VSv9%Wq4`F8@J$q)AcU!cw>5+`5sk*A9?zD!%u zV{*xSb4U8o=1gjHI+3JeV=R}KVj|fQ>)o6)@!Y2Lqo$`bWox=S@+s33Z`%nmRBcS{ zY%|&To-DPpb#zlmbt@9~RxX*#)AL@S^u(=7B$jKpRrbOT*tRU*Vb{g-F+#~Y3#_N> zHH}&zpH1!Dnanoe%BVGlI~i$iN!wywiH_vvWakESEcIB@Oae`~qcXWnsyUNPCQK6c z$GUbV*W$*>q;l3a-1Ic!m3nh`KG{RpK2(>?y2Zv=zA;B2Ntk#xjvFnA<xR4S?&8oV zdr9PWuNhaAR@h}QJsYi6wolS^v~VxQOa~lJtkzuXy6$*9nah!}wn<YgkCCD4t60M3 z?bQ_==2j%&YO$s>*|{#c!?d)((wx1`YH7*Dva!ybdsQ`Af}v*foe{H#>{&;{Od8fE z(Thkn)|HFJ^Qm-~Y1y!8%i8))En6BJo7YELBK2!Gt#2{w);HYOvSI7JTUzejQezUS zovD1R!<tGY>)Ew7-<8mGFb@$nsmWwgT{i6EY21c(B)4|wF)CS;%w$tt`5gx0>1=Nk zjLP9k(sg3i^xWT_>`pe|&N0tpwWGz}Cz~GXj9X!v*R>>4x%QSkg%~bN;$}z7qZDN{ zc&qMwAd?`k#&Wr279pSNFi^=O-a><*%h@DZtps9w(1OOjITMQ~bxo!_*M^8p#_28^ zSJj;vwzoOi8OyY#v&l%TJ?Xl=DVgi;Omh8(WLGkqiZ>^_5)@_#-}*!XiftUB6zR<* zjlCA;_y=}xVw!5)M?zzEnxz@Kq)c}~i@h9Y=U7J(X)4~{Kv(u$%|<k&J3A4vu9eN* zIb3BY;6A!}$AfORT_<wX*~#NEZEY`%%jL5jkafGWA)D^b)ORJm97CV&7;Nb#x_Cz# z_xBQqNeqe%9Swv1!eI&`6S{Mg5_Io8S#U>pvT-_|?=U-)`4-F;3IeD?DcAC7D&K~i z@Rm3_Nw@c=C7y?GTTpN5cmcxvq#3>5PH(%8(Xzy-4O$kQ`YM5eh`T<qsLAyrcssY@ z;=kDrPUEy$_dr)3vB%#A)Mt}e)l#ilgr@agKHXt5d$y*t`OWr%oIKhUM@->Kk1L#R zo$LDhE3qtw0C{BW(xQcBPU%II`Zu`_abIZ3fn)FuOS0X#-^kFa;w~mM7`cY7JS{`$ zt;|o}|K&mVGB~nKCfT2sdT`m>yz+7m^UAMe#wFlsm}JKf1vpRlKI;@7=De4G6XRa~ zt&9`@dd|~B?yZQYQQ=X}(+?NuPEk@DXULw70^*tBJn`J3@I2?Q_uvI3ul;#I$!q*M z#z`-JCo`D_Ip@`TgmJIlGmMiTG>@E1ynZNw93`(G<}*$_+7AxnWapRMruGv*2C&JC zhZ*<UPxo+?y!LNb^4dQSD|wC6y&5I5^FB9gKL;82`tubfFR?@oMi}?{=d{AL-ZvQc z`t3c&z42LOob24J?7YZ0*{S_3_qk+`)+_g-<Ts74#61BelIK?qTfSA{I{vE}Cmt<d z!#MTp%a+0Yko!}ze~ZE&R{YwYsN&anhYx;0@vKt(Pbqng)4dKQvPb4VmFZrG65;o| zS^Ig!2Y-oi@!LvnbAoa4kKiMUr%Ca@;o+&~y0;Xr{r|RyU*z9o-0S}{N?!Z(ea5}x zQe<5EB|bW*aLUT}5Fauw{T2Dk3fJ<uG_{HJHgjL;LHA6QMDKRDXqGBm`@vyc^osln z#=U-^`zlH#ul;Z<<6b{(Wt{90A5;5?;?eka#%VrANRU&H;?a5^S3DXmdWfRNz% ztdIOrB~Ra3NqUKKvS05z#}$vp-&685uX~v2j0b;~@%I&vmM?m6k(ckgsbAZ~NIW0r z&J+Hi!b|Z!O^NK+{+Y+PcO1(ZCmz|msr^=kKSBVfgu;JUKs-Bq_<NMRw)1Hp`9US$ zqWI~)ffCvIkejui@B82%GcNPuD7QJ!xWvEUmp$?_j`CHG$P2z=wo6F%M46i&D;f9t zxmL+*`?o7Rrg#bp*W-@gDBI-aKd$7Xisyun{Anex?RiV#nn%80^Xe@sdChat2cOUP zz~r}9WoH@V-ncDi+^aWI>NfVu<KG?HMEnhk|6wIh^X@p;MHNo#t*l>djFVoCXB4h^ zdKf3YNu~F3#ows#r<D8-g%2uxr^1gaT=(m^!q+MJ6O2pzOWdAfocg8LpAm)Yb>l6? z-=_FKR=8dtE-L&#Df!Z?-2(YX&+9UUYo3I{Q;O#)AAC^ZyOjJ(jEf&exb6hw;s?P` zG49<5Us3#96#r?3w<~-ee}yV~k8<67#zn8-HH?#gIuuWv!aEgy#KZp~*B$lX=NUiE zxabx9q7Q%RT(_af3x9!e>DL+NKj4uU{AtFiU)ugxJUqfb;=#qv(;oa&)_ak0u~X#n z`(>L*Fa2gj(ya>D_JkQ19^v2WBcJfdi~SiT9}}f`o>#bD&ug!7g~-k}CBISOdR}Z- zcwEV66t3qN{o_SS#IJdtRd~V`v7av~T=Tr8aLsd0;hN{7!nK`c{8c{LqxqLAJgw}h zRd`0>>lB_+_*TXxJ`MCxiZCwYD|iRv-ua$U{Cd70P`I}Ll*0A+US?eES?QW%N@(## z5_<%n$2j>%zweYWE<EzR)>03T;11*7eyvdaTU-<DXN|&lD?G|L>8)0Hf^o86<86%7 zd4BT8rD!MLGkSUQK0G~&r(5ZLnsG1BAs?Or#q+4*dC7<8xDU?>#X~>-m-L1Y&s#n` zZ!4ZYA;EL$e78XT(&vN~jMF&MZ`mY0%s9o#UIFox?<<Li_Hp@r)e8Rpaghg??=eOG zV?MXlu>5CPUU2z-Q{?}N<=3&i+`|Yi-+PL@m>OYuiXVO6c#d(B*M2z4IQ4gjkl=Y- z$&+ihqMp(T#=Y@>igB5DB0r+|x40Dc^R&VbDEuvjKdJCD3jfave_!GMMd9Ze_xk4| z<6i$<R`S$exhE>&pCn1Y1fRz^`E8fdyOeR#OFSFtkc;Fn?)BRW55LH-RQ%d+)e7J3 zQrpk%3jaNYXB7UF!k=c`>xV;(i~VhE|A3OGehK~@<KBK9Wt{w@?LV&YKT!6JFfMwZ zV!fvs7yk?Xp5oE`=M=tO@qg^$f0p^rE1aO}Qn%5kjEi28Hw)c*!nOQT#;L#h9_dzv z>v*nJxQ^$9!uKotdlatk2L>1yza8a%J<GV*FZgqcNBixF!gXAoR=AF<_Y|(<>b%0W z{AGoAs(zJ~P5D!=S6^hD{Hb{&3fFq`jEf)I(2mm6N?!9k>ybas^3O3YeiQs94=(&C z6#sv9Roc%H55Jt-PkVR-e_Qb!R6Or1{Aq=MsPI;WUu0bTfdB8prcW7{ehFT7y<6|~ z^Ge1=Uiy2hlGpvEe~3(pc=Y%_uJEtABKGsB!ea`5N#TE}@V6AM`RDOJ7$G}#{FE_H z_GA>#QpU+YcB=3_h@*HkzC!W*H^sA3@q7lj!}IP|#=Yxdwc^+EHHu%)$E_az4D6*8 z@!@~i!!PntAO4KOr_Bo={HVh9yc<!t=6PG;TK;3kB|bmoew}CB>$guCmpByp%Zgw7 zt>gyRPhOsK#wi}OyyGKZ?ISP0n<D!u-sJc0>sVgSb%M*kN1${2A=fnf*}?L{BUKs3 zz482#vgZ*I#`8Ue>vKrahv%Y_*Y8>L%3V_O&ohdDg~IiDxLV<Qer@u>3kuhMIK?>m zr(fxnYykLx6!0wNJmI$}e5Jy*e6_+!UgWkaT+44)ILV6~!-n+IRF{20+rvwM6`juw zL|)3=-ASH7mUBGvVd$YG_6kqNg(u$)1wYStEk6Yhb6K8(JB)knmv|L>MPB~>jJAi? zvGR~hw2}Elek(g;s|R-%T?X+W`Biv23~76a{}l5`J;@V3!nn3a$Ak6*$;<bYVdN<h zk6%2He3AM6;-Ss5xI83(p5?vv&u9NQ9(nPbwx8CMQs(j6FW)bE`ThK3Sg)5~{vD2& zzm(;}%1*LJ-gEUh>i(LlTyJMS){197>pt5gm&FhKs_f4dtMIe8n5k;T@5-vOX)2KT z9aXg`l8{A^^AxM_uXAHpfZ6nP96umhXaCi9)#Pu4Tvq%Fi6ADmKS->ipBqgBtN{Ni zi~Iin^Kj4@p(S5$O;Uw9_e%LBWHU0)1YLp*`8_NEKf^Rhklv_ppL84|JrWN>`#HvW zI9*|UUKW8##LW<gPPd{!oZj~4Mpx>;&(YFT`USlM8REQC0C{qI`cIK`68puD^{Ax0 zN6b_&bzAl5#>h*1fy2nm<iFBpSK<&0lK*DoPuh!nBEV+Sf0Xra=l1fD_EO%0%uM>9 zW&LMZkn~eqX)pTe&UGgJ=Cf|Y-=seQv6=K|sAEVy?!%CN8cMJJeZXeYzn%4qJkw0J zm-6Gt%%uNA)-U}e{d9FNe1d-i*i8DPtY7Shm`&1N%728+O#0==3nMH@`soT;+Kc{U zz-H2ahV^gc_VSSSQa*yrO!`M2a3!KFNcw5+OMB7(U0^fmcYe!l7<C_$pVD4{lgP}Z z-}#Cwq2r&fIHbMk|2{C%U+s!deim52{w|s-NtTj+@)qV+@Mn?Re|n7z(DA(ie_s7p k1M|*(YH@}ZCZrfmT9rhvKnswWsr_;8|KErpKfUe$AHtd+bpQYW literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/zranger.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/zranger.o new file mode 100644 index 0000000000000000000000000000000000000000..bd24ca0092ba73c6c374841bc6ae4214b3bb302b GIT binary patch literal 4200 zcmb`K-ES0C6u{4RKnj8u3Q_@=*@Dob9k)dSOVI3gTUxYyWV?u|#O-u<%1+qbS!QNS z3np%j55}0-1|N(Mra=?HM-w9^U<iMLMuUkD#Ro%-4;b`;#9Ggpxu?DC?)c<scFwuK zdp_>HGjr$m?f#*|O`#C5gy3sfZZQSOuU)p|o*9Q0coG&aesgU>f!PPcp=*DB7MlI5 z6&`K^nE9#+X7BA*iVu`cU;OsMisJA4R~9ksqu!=!Dg@QkJaTH^4pmbTsV(<WfAYht zsb7x1lNvj5#ZKJ)B&FxB*e2`_zly&-_?zDk54Wqz52FX;Q{*3dD}HHS+34k-S6V&Y zbO<)gVU0NYkM+V7+=;viZJlBAAMK4#ZU0$2*Zj|7x*2wa*R^P2eOLTu^Xliq5bFv< zb0iG6+CAU37*8?NKVf`A4M#e<!ja}Z9-CiW+)U$GxcKeTdbHv?IJgd@m*X*2fqfgX z-Hzj!Zi+u#8e2~_wGyh|RgvMk&-9@k0hm=#Q?2Tnd#KNRN_J@PrBvkmD>guTnDRtu zK9?Z|ZISTkF1Yz%IB{*^;_a)ql+2Gb7W!e_4E|<AbMcrCun#bf`jO#q07g=YV*~vu z$QjwQ)E>)@r1a7m1B-a#xK=sCok(u179En39u0{$Hm4h7$OrIh0EdBO@}Sx=aO|X- zwyZ)nubU-x+_F_SZ>Wi`vTco<1+?sJ-gJ$uTd@r_ruB67M7v{JcaPek+r=)lqMe<@ zwQiMqx}!a~LjNUrk6;D-vDnB*Y53*<DEQY%6wFjBk9&Zs)QbWu>);a}3F7tn*Q0+( zs;i2O_|AHq+f9N~oBVf*HfQV<yhCt##0oqn=(6(1S<la7U`X;mupEM`)-1Jr)6Y}S zsaJtD0si$oik>0Ke^824p#F(|8T&V21j|}szJj2Ip`=FwcqM>;5WwlhZ<POX0RJ+8 z-wEJ%1Ng52d=<`{)}ckr|2_00X~lM<adrmq?g0K$06!AIk0Gb=%%LXP<|`Np@Gm1@ zFFjXFPtpb3+xE09?3{$1IouE@z(bjW?zmt~mXnq-J`SdHq-45~$&__lFFO9-c){N@ z)4FpOoGHgOil=nb9d>owg^9wxy@lxHu;IRzb&SG^O2IKs7`AEUmb%C<X_Z{FRIw@! zOj4c!!%dsnvq`H`a^YxC8YYPL83ldnBzhJ&IA!QLuljO=qh_IC77f?19e)Z~n<g;s zxB5%xDn`ZVv(A^iz$2x8$2E((YuO+s;!km4=y-2pD0BSq;o<&tCY|UV>d$x|ie4O~ zn3m`14LE5Vx@$neIy25`(gv=aa3mXtSi-&7v`Ub(%?ZQKh*e+y!gwDgyodBW@m@o> zv`yUCO*Q;^!M7scENoJTB+jvfh64EO5`S9Qq)tnGi^S=DC84@oebc*sENtTZEE1ZN z_%p&LbwlEGkYKqd49c^eA?o`Qm&daL{Yc1P^(_CgP4L?FR0XeFPszVs%JZV&G1NOG zen@bt%ijp<9+do_lKh7Rr}4;NgS6l@9+{sOobo>_<;hEYm&AD=sGaZU!oPOD*9G5# zx<kst`vM(}X*|5Qu@CWx<R29_@!b+<llVGrpsvl&ZB_V?e^6a|FL)dWYWz7KG-s;l z>SL%~+t+!vY}`aN*O+uc%jvET+L+^jW?R%C_ipU~Hp$5&XkjN4JSX;f@2>X9yX*UV zd!ptY7qzTaEE>3X{XatU!X<g+*`UmEx}e;kPD%KFF`{>r)-BFJ=ozu_?=|^=?h&Qp z`@wq$J!8acPjY|P)I}FhYBB9ol(RM-L|r;h$-?!Sb)!K!dl;}5@q4%}G{^He`jL}e zTR$q|`8nb=9MA1I8jaSk%|Echpm3!1qvw|6dHqfyYg9ik>a)K{vlP$m6dH}{kBa(S zhw4)<&c~e2U5)COMg2kSmxbe*mC<Nae^S&R6^>M&PMaLh^{0_hecmU~^yIpz{{{o0 z$(Kad!qx8(*EVrO?+Z=mW7=<P>(jq&wfCM<G_Rs7z`I<?Z!XmpO*}I-j=v-3|2{hg G#QzH`)tLAI literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/zranger2.o b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/uart/build/zranger2.o new file mode 100644 index 0000000000000000000000000000000000000000..78fad7ca3378b8c09a6d1e575e66c2ec07ea5443 GIT binary patch literal 6152 zcmeI0Uu+a*5Wwed1q-4At%!oh7ElV<qb-nlhJ-uXQV1<H*TX+WJ+^n-_R{<3?iO1? zy`m4skk~2@#0SG0l*Giu1WAO1L?3uE#6%Ml6N>mi3=a~5NMciGcE34>yIWs;GGQ*e zGvDu<`DXUpy>Gv}_d2_G1_J?L3BcEIuf-JLQvE$U>Y7nl0*lF-1c*j1YRR8g>DrI8 zhc8UeYA|)HFEEWElLv#*NC{xet-jdw?BQ=ulV5`y1CtZM=v|DT!sGa=m0*=LNR*Ia z{>et<x9j2VXwd5?HV;ZaP(Sr`psnE%Y%9enzO?ZA4*)}-lMS#s6j;0|)Ci@x5rhck zhUJZ+lk?%i?fU3lu0!VH`Y^tMu7i)+!)MFaLv<g=dTwbAXKo(|PT#%~nEF!-PTfgq z(|4`~rj}#>^>q*Be%~}NcVjcmQY|y+OFD+NupQWXtZXwQpZ1SW$A9fP8XxFAWyP+3 z7B|wTtPHFR?ZIOM9y8nFZUfG(u6frSI1>GIMtjm7f9^^kLN#C2o;Wk3)w@i`oHQ<= zpIgh7SOn(gwp`Vgm3^*nj=jVFtl{UzH%?;ghfCodSiU|)v8AQa@vFt7@l_BQsr!2_ zQ3q>6FsX+o=0`8oE!Y@>h#rEv#t>Xw?fNgmdMR!K#|kbEhajeh8k<&!8tXQ={QJ4N zC$S&;<83eM{mtpZTY23!^LD|~5A56X`a<d>>5s?uc6G+vyjE@how42B9FaCtBjh`f z>W>@wA=6Tkwo@o3xswNbpdZY@gBkc=%)t4_s>@tdjeN<3PtULqFZpojYHxp0Z|d5+ zUr!VY+0?L+$?Jo-YB|HE9&0XIg~3b~Eh{ygam<u6YMFW@+}7OI(i#c3w&_iVm1{<; zW&L{M;Z~h`T3gz-`X%%@zW?AMxH(tLORM?D2GH<ROEes*QoOmOEY+gHyejy(OZ<5C z_)F10Ao6mirxfQ1)~gk-bMpWMl_sUZe9`huubyh&jNJj@|D~7`4IcIxr<z~Gf&;?; z1re#i0@3nJubyg7y&62?<6q5N(K8_YcZo<19u+Om+>UA~MzHXAq+4-!$A<QI%HdVi z%oK7}!H2))!{7JepZM_4kW-yAs7YQ^C7(jORy|+&@N+)=k`KS)!~gW*Yq73c^=$Lu zdwqD^hY$Gh2_JsUhkxP2&-(CheE2WOmx$+?zkl$y<!z_JDOfuOYtxXicjq$>m}ABE zf;l({Zhtas*bb!4Ly$}s4a>;c-lpqqwHZs8*v$<$KH1g1Z%3><xo_vrzRpB45!=z- znZyxNBRfWIIF#MGIomqsdZr4vJ<OWDqYkdR7MMjVlXnKoqa_S`1jgvxZkdK-Lbfn8 z2==(`n7NmYjML{BmIE(!Z{6J8n(V{vV2^3oxIE{~{5@<s9U0p(@+q^YkT%QSrX!pa znOr76v|}_qggBG33VkM)mbS~@lt}n{MRl1@B9j_vFN|Wkp0)%WqEb7|tTDbn?_{zZ zjea7w!*GnaX{5)6yYQr0#ab!?yj#&{x;IDNn9ls0qvojDf%|OtR_xAq+D;~CI0XyR zR_2gtCHW55+$PuKbHQsfepSl$vI@SEI#DY9b(aEE`fpL3{GV1fDPCWR^BP8c8=X)h z$X9r#dyXpmi3<M?#aAHb+6eV3PUAeIY*GnjQ(pNtc|~y=U-E;3%lSzwPI>7E56iGJ zczj*8i%L^HtCUU3Q8wq*Rr>>_X?$jcCIxR)HmQ@!uAKk#idW9VMa8+!7S;YvX|9L) zWyPPydgS%q5aY=E_=gxr@<kX=LV4wUu2h_^m-YrMv_6v%U*nnXxkd1`g44Q9LjKQs zrhD!X{5ipQ3BFG7qT)0Uvd%H#-z5A$5PZGhCj{Rh_({R#IHv{QDE!Y0{=DFq1ef!3 zS#Wv1zX?uzCzb}a0i$^fGeo^oa5+C)1m7h5`F%ovInnoszgK*X#A#2+!p|4+<qU-; z?(MZaSUG;L^3|38x4iN`^7_O6!zv!a_IS=Q22eYer-#|Ha4`=%=9mNFG_Kna9<Xf) zTLo&6du#Xw2&Ymx50kUogJI}|jxNC$Ux&LMhwopHy>9oN8g~E32&W1;_ua*n{U@zs zG*0DxYa0z1r4!0Fbw9mU^`3~<Vw%4wJ1DKI-)+5Wa;Zsq_&)JHrDu@1*q&nx;7CPY z7vhP0rO-1^WBSFH|4>pv@?I12_SpdCKbn+ZN#(axn-$m3bwshFR{ejec=@}7#^89e zNqX?86@Qw(Bq;nmdadgCUD#1;{)_a(3x)bgX#O9@gY)zJCy~|4Kcn)qKf1Y6+3rVL zEB`r_pYu?D`c=g7%-=;;EB|$se;4*k;do}_Xw=GoS>->d94SBj%Hnv={}D3E&+84E zuC&l(p&am3`AohfQrCJ^Csq6j^}x|uML8?;)0|X3yNIAky&P|HB7!ItP298Bj&D)_ M+tVMwQYz#B0m_&eRR910 literal 0 HcmV?d00001 diff --git a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/utils/src/cf_math.h b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/utils/src/cf_math.h index 4a8aae466..b99fe11bf 100644 --- a/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/utils/src/cf_math.h +++ b/uboot-compiler/bm_crazyflie/FreeRTOS/Demo/CORTEX_A72_64-bit_Raspberrypi4/utils/src/cf_math.h @@ -36,10 +36,9 @@ #pragma GCC diagnostic pop #include "cfassert.h" - - -// #define DEG_TO_RAD (PI/180.0f) -// #define RAD_TO_DEG (180.0f/PI) +//COMMENTED FIRMWARE +#define DEG_TO_RAD (3.14/180.0f) +#define RAD_TO_DEG (180.0f/3.14) #define MIN(a, b) ((b) < (a) ? (b) : (a)) #define MAX(a, b) ((b) > (a) ? (b) : (a)) -- GitLab